1 /*
2 Bullet Continuous Collision Detection and Physics Library
3 Copyright (c) 2003-2006 Erwin Coumans  https://bulletphysics.org
4 
5 This software is provided 'as-is', without any express or implied warranty.
6 In no event will the authors be held liable for any damages arising from the use of this software.
7 Permission is granted to anyone to use this software for any purpose,
8 including commercial applications, and to alter it and redistribute it freely,
9 subject to the following restrictions:
10 
11 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
12 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
13 3. This notice may not be removed or altered from any source distribution.
14 */
15 
16 #ifndef BT_RIGIDBODY_H
17 #define BT_RIGIDBODY_H
18 
19 #include "LinearMath/btAlignedObjectArray.h"
20 #include "LinearMath/btTransform.h"
21 #include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
22 #include "BulletCollision/CollisionDispatch/btCollisionObject.h"
23 
24 class btCollisionShape;
25 class btMotionState;
26 class btTypedConstraint;
27 
28 extern btScalar gDeactivationTime;
29 extern bool gDisableDeactivation;
30 
31 #ifdef BT_USE_DOUBLE_PRECISION
32 #define btRigidBodyData btRigidBodyDoubleData
33 #define btRigidBodyDataName "btRigidBodyDoubleData"
34 #else
35 #define btRigidBodyData btRigidBodyFloatData
36 #define btRigidBodyDataName "btRigidBodyFloatData"
37 #endif  //BT_USE_DOUBLE_PRECISION
38 
39 enum btRigidBodyFlags
40 {
41 	BT_DISABLE_WORLD_GRAVITY = 1,
42 	///BT_ENABLE_GYROPSCOPIC_FORCE flags is enabled by default in Bullet 2.83 and onwards.
43 	///and it BT_ENABLE_GYROPSCOPIC_FORCE becomes equivalent to BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY
44 	///See Demos/GyroscopicDemo and computeGyroscopicImpulseImplicit
45 	BT_ENABLE_GYROSCOPIC_FORCE_EXPLICIT = 2,
46 	BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_WORLD = 4,
47 	BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY = 8,
48 	BT_ENABLE_GYROPSCOPIC_FORCE = BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY,
49 };
50 
51 ///The btRigidBody is the main class for rigid body objects. It is derived from btCollisionObject, so it keeps a pointer to a btCollisionShape.
52 ///It is recommended for performance and memory use to share btCollisionShape objects whenever possible.
53 ///There are 3 types of rigid bodies:
54 ///- A) Dynamic rigid bodies, with positive mass. Motion is controlled by rigid body dynamics.
55 ///- B) Fixed objects with zero mass. They are not moving (basically collision objects)
56 ///- C) Kinematic objects, which are objects without mass, but the user can move them. There is one-way interaction, and Bullet calculates a velocity based on the timestep and previous and current world transform.
57 ///Bullet automatically deactivates dynamic rigid bodies, when the velocity is below a threshold for a given time.
58 ///Deactivated (sleeping) rigid bodies don't take any processing time, except a minor broadphase collision detection impact (to allow active objects to activate/wake up sleeping objects)
59 class btRigidBody : public btCollisionObject
60 {
61 	btMatrix3x3 m_invInertiaTensorWorld;
62 	btVector3 m_linearVelocity;
63 	btVector3 m_angularVelocity;
64 	btScalar m_inverseMass;
65 	btVector3 m_linearFactor;
66 
67 	btVector3 m_gravity;
68 	btVector3 m_gravity_acceleration;
69 	btVector3 m_invInertiaLocal;
70 	btVector3 m_totalForce;
71 	btVector3 m_totalTorque;
72 
73 	btScalar m_linearDamping;
74 	btScalar m_angularDamping;
75 
76 	bool m_additionalDamping;
77 	btScalar m_additionalDampingFactor;
78 	btScalar m_additionalLinearDampingThresholdSqr;
79 	btScalar m_additionalAngularDampingThresholdSqr;
80 	btScalar m_additionalAngularDampingFactor;
81 
82 	btScalar m_linearSleepingThreshold;
83 	btScalar m_angularSleepingThreshold;
84 
85 	//m_optionalMotionState allows to automatic synchronize the world transform for active objects
86 	btMotionState* m_optionalMotionState;
87 
88 	//keep track of typed constraints referencing this rigid body, to disable collision between linked bodies
89 	btAlignedObjectArray<btTypedConstraint*> m_constraintRefs;
90 
91 	int m_rigidbodyFlags;
92 
93 	int m_debugBodyId;
94 
95 protected:
96 	ATTRIBUTE_ALIGNED16(btVector3 m_deltaLinearVelocity);
97 	btVector3 m_deltaAngularVelocity;
98 	btVector3 m_angularFactor;
99 	btVector3 m_invMass;
100 	btVector3 m_pushVelocity;
101 	btVector3 m_turnVelocity;
102 
103 public:
104 	///The btRigidBodyConstructionInfo structure provides information to create a rigid body. Setting mass to zero creates a fixed (non-dynamic) rigid body.
105 	///For dynamic objects, you can use the collision shape to approximate the local inertia tensor, otherwise use the zero vector (default argument)
106 	///You can use the motion state to synchronize the world transform between physics and graphics objects.
107 	///And if the motion state is provided, the rigid body will initialize its initial world transform from the motion state,
108 	///m_startWorldTransform is only used when you don't provide a motion state.
109 	struct btRigidBodyConstructionInfo
110 	{
111 		btScalar m_mass;
112 
113 		///When a motionState is provided, the rigid body will initialize its world transform from the motion state
114 		///In this case, m_startWorldTransform is ignored.
115 		btMotionState* m_motionState;
116 		btTransform m_startWorldTransform;
117 
118 		btCollisionShape* m_collisionShape;
119 		btVector3 m_localInertia;
120 		btScalar m_linearDamping;
121 		btScalar m_angularDamping;
122 
123 		///best simulation results when friction is non-zero
124 		btScalar m_friction;
125 		///the m_rollingFriction prevents rounded shapes, such as spheres, cylinders and capsules from rolling forever.
126 		///See Bullet/Demos/RollingFrictionDemo for usage
127 		btScalar m_rollingFriction;
128 		btScalar m_spinningFriction;  //torsional friction around contact normal
129 
130 		///best simulation results using zero restitution.
131 		btScalar m_restitution;
132 
133 		btScalar m_linearSleepingThreshold;
134 		btScalar m_angularSleepingThreshold;
135 
136 		//Additional damping can help avoiding lowpass jitter motion, help stability for ragdolls etc.
137 		//Such damping is undesirable, so once the overall simulation quality of the rigid body dynamics system has improved, this should become obsolete
138 		bool m_additionalDamping;
139 		btScalar m_additionalDampingFactor;
140 		btScalar m_additionalLinearDampingThresholdSqr;
141 		btScalar m_additionalAngularDampingThresholdSqr;
142 		btScalar m_additionalAngularDampingFactor;
143 
m_massbtRigidBodyConstructionInfo144 		btRigidBodyConstructionInfo(btScalar mass, btMotionState* motionState, btCollisionShape* collisionShape, const btVector3& localInertia = btVector3(0, 0, 0)) : m_mass(mass),
145 																																									   m_motionState(motionState),
146 																																									   m_collisionShape(collisionShape),
147 																																									   m_localInertia(localInertia),
148 																																									   m_linearDamping(btScalar(0.)),
149 																																									   m_angularDamping(btScalar(0.)),
150 																																									   m_friction(btScalar(0.5)),
151 																																									   m_rollingFriction(btScalar(0)),
152 																																									   m_spinningFriction(btScalar(0)),
153 																																									   m_restitution(btScalar(0.)),
154 																																									   m_linearSleepingThreshold(btScalar(0.8)),
155 																																									   m_angularSleepingThreshold(btScalar(1.f)),
156 																																									   m_additionalDamping(false),
157 																																									   m_additionalDampingFactor(btScalar(0.005)),
158 																																									   m_additionalLinearDampingThresholdSqr(btScalar(0.01)),
159 																																									   m_additionalAngularDampingThresholdSqr(btScalar(0.01)),
160 																																									   m_additionalAngularDampingFactor(btScalar(0.01))
161 		{
162 			m_startWorldTransform.setIdentity();
163 		}
164 	};
165 
166 	///btRigidBody constructor using construction info
167 	btRigidBody(const btRigidBodyConstructionInfo& constructionInfo);
168 
169 	///btRigidBody constructor for backwards compatibility.
170 	///To specify friction (etc) during rigid body construction, please use the other constructor (using btRigidBodyConstructionInfo)
171 	btRigidBody(btScalar mass, btMotionState* motionState, btCollisionShape* collisionShape, const btVector3& localInertia = btVector3(0, 0, 0));
172 
~btRigidBody()173 	virtual ~btRigidBody()
174 	{
175 		//No constraints should point to this rigidbody
176 		//Remove constraints from the dynamics world before you delete the related rigidbodies.
177 		btAssert(m_constraintRefs.size() == 0);
178 	}
179 
180 protected:
181 	///setupRigidBody is only used internally by the constructor
182 	void setupRigidBody(const btRigidBodyConstructionInfo& constructionInfo);
183 
184 public:
185 	void proceedToTransform(const btTransform& newTrans);
186 
187 	///to keep collision detection and dynamics separate we don't store a rigidbody pointer
188 	///but a rigidbody is derived from btCollisionObject, so we can safely perform an upcast
upcast(const btCollisionObject * colObj)189 	static const btRigidBody* upcast(const btCollisionObject* colObj)
190 	{
191 		if (colObj->getInternalType() & btCollisionObject::CO_RIGID_BODY)
192 			return (const btRigidBody*)colObj;
193 		return 0;
194 	}
upcast(btCollisionObject * colObj)195 	static btRigidBody* upcast(btCollisionObject* colObj)
196 	{
197 		if (colObj->getInternalType() & btCollisionObject::CO_RIGID_BODY)
198 			return (btRigidBody*)colObj;
199 		return 0;
200 	}
201 
202 	/// continuous collision detection needs prediction
203 	void predictIntegratedTransform(btScalar step, btTransform& predictedTransform);
204 
205 	void saveKinematicState(btScalar step);
206 
207 	void applyGravity();
208 
209     void clearGravity();
210 
211 	void setGravity(const btVector3& acceleration);
212 
getGravity()213 	const btVector3& getGravity() const
214 	{
215 		return m_gravity_acceleration;
216 	}
217 
218 	void setDamping(btScalar lin_damping, btScalar ang_damping);
219 
getLinearDamping()220 	btScalar getLinearDamping() const
221 	{
222 		return m_linearDamping;
223 	}
224 
getAngularDamping()225 	btScalar getAngularDamping() const
226 	{
227 		return m_angularDamping;
228 	}
229 
getLinearSleepingThreshold()230 	btScalar getLinearSleepingThreshold() const
231 	{
232 		return m_linearSleepingThreshold;
233 	}
234 
getAngularSleepingThreshold()235 	btScalar getAngularSleepingThreshold() const
236 	{
237 		return m_angularSleepingThreshold;
238 	}
239 
240 	void applyDamping(btScalar timeStep);
241 
getCollisionShape()242 	SIMD_FORCE_INLINE const btCollisionShape* getCollisionShape() const
243 	{
244 		return m_collisionShape;
245 	}
246 
getCollisionShape()247 	SIMD_FORCE_INLINE btCollisionShape* getCollisionShape()
248 	{
249 		return m_collisionShape;
250 	}
251 
252 	void setMassProps(btScalar mass, const btVector3& inertia);
253 
getLinearFactor()254 	const btVector3& getLinearFactor() const
255 	{
256 		return m_linearFactor;
257 	}
setLinearFactor(const btVector3 & linearFactor)258 	void setLinearFactor(const btVector3& linearFactor)
259 	{
260 		m_linearFactor = linearFactor;
261 		m_invMass = m_linearFactor * m_inverseMass;
262 	}
getInvMass()263 	btScalar getInvMass() const { return m_inverseMass; }
getMass()264 	btScalar getMass() const { return m_inverseMass == btScalar(0.) ? btScalar(0.) : btScalar(1.0) / m_inverseMass; }
getInvInertiaTensorWorld()265 	const btMatrix3x3& getInvInertiaTensorWorld() const
266 	{
267 		return m_invInertiaTensorWorld;
268 	}
269 
270 	void integrateVelocities(btScalar step);
271 
272 	void setCenterOfMassTransform(const btTransform& xform);
273 
applyCentralForce(const btVector3 & force)274 	void applyCentralForce(const btVector3& force)
275 	{
276 		m_totalForce += force * m_linearFactor;
277 	}
278 
getTotalForce()279 	const btVector3& getTotalForce() const
280 	{
281 		return m_totalForce;
282 	};
283 
getTotalTorque()284 	const btVector3& getTotalTorque() const
285 	{
286 		return m_totalTorque;
287 	};
288 
getInvInertiaDiagLocal()289 	const btVector3& getInvInertiaDiagLocal() const
290 	{
291 		return m_invInertiaLocal;
292 	};
293 
setInvInertiaDiagLocal(const btVector3 & diagInvInertia)294 	void setInvInertiaDiagLocal(const btVector3& diagInvInertia)
295 	{
296 		m_invInertiaLocal = diagInvInertia;
297 	}
298 
setSleepingThresholds(btScalar linear,btScalar angular)299 	void setSleepingThresholds(btScalar linear, btScalar angular)
300 	{
301 		m_linearSleepingThreshold = linear;
302 		m_angularSleepingThreshold = angular;
303 	}
304 
applyTorque(const btVector3 & torque)305 	void applyTorque(const btVector3& torque)
306 	{
307 		m_totalTorque += torque * m_angularFactor;
308 		#if defined(BT_CLAMP_VELOCITY_TO) && BT_CLAMP_VELOCITY_TO > 0
309 		clampVelocity(m_totalTorque);
310 		#endif
311 	}
312 
applyForce(const btVector3 & force,const btVector3 & rel_pos)313 	void applyForce(const btVector3& force, const btVector3& rel_pos)
314 	{
315 		applyCentralForce(force);
316 		applyTorque(rel_pos.cross(force * m_linearFactor));
317 	}
318 
applyCentralImpulse(const btVector3 & impulse)319 	void applyCentralImpulse(const btVector3& impulse)
320 	{
321 		m_linearVelocity += impulse * m_linearFactor * m_inverseMass;
322 		#if defined(BT_CLAMP_VELOCITY_TO) && BT_CLAMP_VELOCITY_TO > 0
323 		clampVelocity(m_linearVelocity);
324 		#endif
325 	}
326 
applyTorqueImpulse(const btVector3 & torque)327 	void applyTorqueImpulse(const btVector3& torque)
328 	{
329 		m_angularVelocity += m_invInertiaTensorWorld * torque * m_angularFactor;
330 		#if defined(BT_CLAMP_VELOCITY_TO) && BT_CLAMP_VELOCITY_TO > 0
331 		clampVelocity(m_angularVelocity);
332 		#endif
333 	}
334 
applyImpulse(const btVector3 & impulse,const btVector3 & rel_pos)335 	void applyImpulse(const btVector3& impulse, const btVector3& rel_pos)
336 	{
337 		if (m_inverseMass != btScalar(0.))
338 		{
339 			applyCentralImpulse(impulse);
340 			if (m_angularFactor)
341 			{
342 				applyTorqueImpulse(rel_pos.cross(impulse * m_linearFactor));
343 			}
344 		}
345 	}
346 
applyPushImpulse(const btVector3 & impulse,const btVector3 & rel_pos)347     void applyPushImpulse(const btVector3& impulse, const btVector3& rel_pos)
348     {
349         if (m_inverseMass != btScalar(0.))
350         {
351             applyCentralPushImpulse(impulse);
352             if (m_angularFactor)
353             {
354                 applyTorqueTurnImpulse(rel_pos.cross(impulse * m_linearFactor));
355             }
356         }
357     }
358 
getPushVelocity()359     btVector3 getPushVelocity() const
360     {
361         return m_pushVelocity;
362     }
363 
getTurnVelocity()364     btVector3 getTurnVelocity() const
365     {
366         return m_turnVelocity;
367     }
368 
setPushVelocity(const btVector3 & v)369     void setPushVelocity(const btVector3& v)
370     {
371         m_pushVelocity = v;
372     }
373 
374     #if defined(BT_CLAMP_VELOCITY_TO) && BT_CLAMP_VELOCITY_TO > 0
clampVelocity(btVector3 & v)375     void clampVelocity(btVector3& v) const {
376         v.setX(
377             fmax(-BT_CLAMP_VELOCITY_TO,
378                  fmin(BT_CLAMP_VELOCITY_TO, v.getX()))
379         );
380         v.setY(
381             fmax(-BT_CLAMP_VELOCITY_TO,
382                  fmin(BT_CLAMP_VELOCITY_TO, v.getY()))
383         );
384         v.setZ(
385             fmax(-BT_CLAMP_VELOCITY_TO,
386                  fmin(BT_CLAMP_VELOCITY_TO, v.getZ()))
387         );
388     }
389     #endif
390 
setTurnVelocity(const btVector3 & v)391     void setTurnVelocity(const btVector3& v)
392     {
393         m_turnVelocity = v;
394         #if defined(BT_CLAMP_VELOCITY_TO) && BT_CLAMP_VELOCITY_TO > 0
395         clampVelocity(m_turnVelocity);
396         #endif
397     }
398 
applyCentralPushImpulse(const btVector3 & impulse)399     void applyCentralPushImpulse(const btVector3& impulse)
400     {
401         m_pushVelocity += impulse * m_linearFactor * m_inverseMass;
402         #if defined(BT_CLAMP_VELOCITY_TO) && BT_CLAMP_VELOCITY_TO > 0
403         clampVelocity(m_pushVelocity);
404         #endif
405     }
406 
applyTorqueTurnImpulse(const btVector3 & torque)407     void applyTorqueTurnImpulse(const btVector3& torque)
408     {
409         m_turnVelocity += m_invInertiaTensorWorld * torque * m_angularFactor;
410         #if defined(BT_CLAMP_VELOCITY_TO) && BT_CLAMP_VELOCITY_TO > 0
411         clampVelocity(m_turnVelocity);
412         #endif
413     }
414 
clearForces()415 	void clearForces()
416 	{
417 		m_totalForce.setValue(btScalar(0.0), btScalar(0.0), btScalar(0.0));
418 		m_totalTorque.setValue(btScalar(0.0), btScalar(0.0), btScalar(0.0));
419 	}
420 
421 	void updateInertiaTensor();
422 
getCenterOfMassPosition()423 	const btVector3& getCenterOfMassPosition() const
424 	{
425 		return m_worldTransform.getOrigin();
426 	}
427 	btQuaternion getOrientation() const;
428 
getCenterOfMassTransform()429 	const btTransform& getCenterOfMassTransform() const
430 	{
431 		return m_worldTransform;
432 	}
getLinearVelocity()433 	const btVector3& getLinearVelocity() const
434 	{
435 		return m_linearVelocity;
436 	}
getAngularVelocity()437 	const btVector3& getAngularVelocity() const
438 	{
439 		return m_angularVelocity;
440 	}
441 
setLinearVelocity(const btVector3 & lin_vel)442 	inline void setLinearVelocity(const btVector3& lin_vel)
443 	{
444 		m_updateRevision++;
445 		m_linearVelocity = lin_vel;
446 		#if defined(BT_CLAMP_VELOCITY_TO) && BT_CLAMP_VELOCITY_TO > 0
447 		clampVelocity(m_linearVelocity);
448 		#endif
449 	}
450 
setAngularVelocity(const btVector3 & ang_vel)451 	inline void setAngularVelocity(const btVector3& ang_vel)
452 	{
453 		m_updateRevision++;
454 		m_angularVelocity = ang_vel;
455 		#if defined(BT_CLAMP_VELOCITY_TO) && BT_CLAMP_VELOCITY_TO > 0
456 		clampVelocity(m_angularVelocity);
457 		#endif
458 	}
459 
getVelocityInLocalPoint(const btVector3 & rel_pos)460 	btVector3 getVelocityInLocalPoint(const btVector3& rel_pos) const
461 	{
462 		//we also calculate lin/ang velocity for kinematic objects
463 		return m_linearVelocity + m_angularVelocity.cross(rel_pos);
464 
465 		//for kinematic objects, we could also use use:
466 		//		return 	(m_worldTransform(rel_pos) - m_interpolationWorldTransform(rel_pos)) / m_kinematicTimeStep;
467 	}
468 
getPushVelocityInLocalPoint(const btVector3 & rel_pos)469     btVector3 getPushVelocityInLocalPoint(const btVector3& rel_pos) const
470     {
471         //we also calculate lin/ang velocity for kinematic objects
472         return m_pushVelocity + m_turnVelocity.cross(rel_pos);
473     }
474 
translate(const btVector3 & v)475 	void translate(const btVector3& v)
476 	{
477 		m_worldTransform.getOrigin() += v;
478 	}
479 
480 	void getAabb(btVector3& aabbMin, btVector3& aabbMax) const;
481 
computeImpulseDenominator(const btVector3 & pos,const btVector3 & normal)482 	SIMD_FORCE_INLINE btScalar computeImpulseDenominator(const btVector3& pos, const btVector3& normal) const
483 	{
484 		btVector3 r0 = pos - getCenterOfMassPosition();
485 
486 		btVector3 c0 = (r0).cross(normal);
487 
488 		btVector3 vec = (c0 * getInvInertiaTensorWorld()).cross(r0);
489 
490 		return m_inverseMass + normal.dot(vec);
491 	}
492 
computeAngularImpulseDenominator(const btVector3 & axis)493 	SIMD_FORCE_INLINE btScalar computeAngularImpulseDenominator(const btVector3& axis) const
494 	{
495 		btVector3 vec = axis * getInvInertiaTensorWorld();
496 		return axis.dot(vec);
497 	}
498 
updateDeactivation(btScalar timeStep)499 	SIMD_FORCE_INLINE void updateDeactivation(btScalar timeStep)
500 	{
501 		if ((getActivationState() == ISLAND_SLEEPING) || (getActivationState() == DISABLE_DEACTIVATION))
502 			return;
503 
504 		if ((getLinearVelocity().length2() < m_linearSleepingThreshold * m_linearSleepingThreshold) &&
505 			(getAngularVelocity().length2() < m_angularSleepingThreshold * m_angularSleepingThreshold))
506 		{
507 			m_deactivationTime += timeStep;
508 		}
509 		else
510 		{
511 			m_deactivationTime = btScalar(0.);
512 			setActivationState(0);
513 		}
514 	}
515 
wantsSleeping()516 	SIMD_FORCE_INLINE bool wantsSleeping()
517 	{
518 		if (getActivationState() == DISABLE_DEACTIVATION)
519 			return false;
520 
521 		//disable deactivation
522 		if (gDisableDeactivation || (gDeactivationTime == btScalar(0.)))
523 			return false;
524 
525 		if ((getActivationState() == ISLAND_SLEEPING) || (getActivationState() == WANTS_DEACTIVATION))
526 			return true;
527 
528 		if (m_deactivationTime > gDeactivationTime)
529 		{
530 			return true;
531 		}
532 		return false;
533 	}
534 
getBroadphaseProxy()535 	const btBroadphaseProxy* getBroadphaseProxy() const
536 	{
537 		return m_broadphaseHandle;
538 	}
getBroadphaseProxy()539 	btBroadphaseProxy* getBroadphaseProxy()
540 	{
541 		return m_broadphaseHandle;
542 	}
setNewBroadphaseProxy(btBroadphaseProxy * broadphaseProxy)543 	void setNewBroadphaseProxy(btBroadphaseProxy* broadphaseProxy)
544 	{
545 		m_broadphaseHandle = broadphaseProxy;
546 	}
547 
548 	//btMotionState allows to automatic synchronize the world transform for active objects
getMotionState()549 	btMotionState* getMotionState()
550 	{
551 		return m_optionalMotionState;
552 	}
getMotionState()553 	const btMotionState* getMotionState() const
554 	{
555 		return m_optionalMotionState;
556 	}
setMotionState(btMotionState * motionState)557 	void setMotionState(btMotionState* motionState)
558 	{
559 		m_optionalMotionState = motionState;
560 		if (m_optionalMotionState)
561 			motionState->getWorldTransform(m_worldTransform);
562 	}
563 
564 	//for experimental overriding of friction/contact solver func
565 	int m_contactSolverType;
566 	int m_frictionSolverType;
567 
setAngularFactor(const btVector3 & angFac)568 	void setAngularFactor(const btVector3& angFac)
569 	{
570 		m_updateRevision++;
571 		m_angularFactor = angFac;
572 	}
573 
setAngularFactor(btScalar angFac)574 	void setAngularFactor(btScalar angFac)
575 	{
576 		m_updateRevision++;
577 		m_angularFactor.setValue(angFac, angFac, angFac);
578 	}
getAngularFactor()579 	const btVector3& getAngularFactor() const
580 	{
581 		return m_angularFactor;
582 	}
583 
584 	//is this rigidbody added to a btCollisionWorld/btDynamicsWorld/btBroadphase?
isInWorld()585 	bool isInWorld() const
586 	{
587 		return (getBroadphaseProxy() != 0);
588 	}
589 
590 	void addConstraintRef(btTypedConstraint* c);
591 	void removeConstraintRef(btTypedConstraint* c);
592 
getConstraintRef(int index)593 	btTypedConstraint* getConstraintRef(int index)
594 	{
595 		return m_constraintRefs[index];
596 	}
597 
getNumConstraintRefs()598 	int getNumConstraintRefs() const
599 	{
600 		return m_constraintRefs.size();
601 	}
602 
setFlags(int flags)603 	void setFlags(int flags)
604 	{
605 		m_rigidbodyFlags = flags;
606 	}
607 
getFlags()608 	int getFlags() const
609 	{
610 		return m_rigidbodyFlags;
611 	}
612 
613 	///perform implicit force computation in world space
614 	btVector3 computeGyroscopicImpulseImplicit_World(btScalar dt) const;
615 
616 	///perform implicit force computation in body space (inertial frame)
617 	btVector3 computeGyroscopicImpulseImplicit_Body(btScalar step) const;
618 
619 	///explicit version is best avoided, it gains energy
620 	btVector3 computeGyroscopicForceExplicit(btScalar maxGyroscopicForce) const;
621 	btVector3 getLocalInertia() const;
622 
623 	///////////////////////////////////////////////
624 
625 	virtual int calculateSerializeBufferSize() const;
626 
627 	///fills the dataBuffer and returns the struct name (and 0 on failure)
628 	virtual const char* serialize(void* dataBuffer, class btSerializer* serializer) const;
629 
630 	virtual void serializeSingleObject(class btSerializer* serializer) const;
631 };
632 
633 //@todo add m_optionalMotionState and m_constraintRefs to btRigidBodyData
634 ///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
635 struct btRigidBodyFloatData
636 {
637 	btCollisionObjectFloatData m_collisionObjectData;
638 	btMatrix3x3FloatData m_invInertiaTensorWorld;
639 	btVector3FloatData m_linearVelocity;
640 	btVector3FloatData m_angularVelocity;
641 	btVector3FloatData m_angularFactor;
642 	btVector3FloatData m_linearFactor;
643 	btVector3FloatData m_gravity;
644 	btVector3FloatData m_gravity_acceleration;
645 	btVector3FloatData m_invInertiaLocal;
646 	btVector3FloatData m_totalForce;
647 	btVector3FloatData m_totalTorque;
648 	float m_inverseMass;
649 	float m_linearDamping;
650 	float m_angularDamping;
651 	float m_additionalDampingFactor;
652 	float m_additionalLinearDampingThresholdSqr;
653 	float m_additionalAngularDampingThresholdSqr;
654 	float m_additionalAngularDampingFactor;
655 	float m_linearSleepingThreshold;
656 	float m_angularSleepingThreshold;
657 	int m_additionalDamping;
658 };
659 
660 ///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
661 struct btRigidBodyDoubleData
662 {
663 	btCollisionObjectDoubleData m_collisionObjectData;
664 	btMatrix3x3DoubleData m_invInertiaTensorWorld;
665 	btVector3DoubleData m_linearVelocity;
666 	btVector3DoubleData m_angularVelocity;
667 	btVector3DoubleData m_angularFactor;
668 	btVector3DoubleData m_linearFactor;
669 	btVector3DoubleData m_gravity;
670 	btVector3DoubleData m_gravity_acceleration;
671 	btVector3DoubleData m_invInertiaLocal;
672 	btVector3DoubleData m_totalForce;
673 	btVector3DoubleData m_totalTorque;
674 	double m_inverseMass;
675 	double m_linearDamping;
676 	double m_angularDamping;
677 	double m_additionalDampingFactor;
678 	double m_additionalLinearDampingThresholdSqr;
679 	double m_additionalAngularDampingThresholdSqr;
680 	double m_additionalAngularDampingFactor;
681 	double m_linearSleepingThreshold;
682 	double m_angularSleepingThreshold;
683 	int m_additionalDamping;
684 	char m_padding[4];
685 };
686 
687 #endif  //BT_RIGIDBODY_H
688