com.bulletphysics.dynamics
Class RigidBody

java.lang.Object
  extended by com.bulletphysics.collision.dispatch.CollisionObject
      extended by com.bulletphysics.dynamics.RigidBody

public class RigidBody
extends CollisionObject

RigidBody is the main class for rigid body objects. It is derived from CollisionObject, so it keeps reference to CollisionShape.

It is recommended for performance and memory use to share CollisionShape objects whenever possible.

There are 3 types of rigid bodies:

  1. Dynamic rigid bodies, with positive mass. Motion is controlled by rigid body dynamics.
  2. Fixed objects with zero mass. They are not moving (basically collision objects).
  3. Kinematic objects, which are objects without mass, but the user can move them. There is on-way interaction, and Bullet calculates a velocity based on the timestep and previous and current world transform.
Bullet automatically deactivates dynamic rigid bodies, when the velocity is below a threshold for a given time.

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).


Field Summary
 int contactSolverType
           
 int debugBodyId
           
 int frictionSolverType
           
 
Fields inherited from class com.bulletphysics.collision.dispatch.CollisionObject
ACTIVE_TAG, DISABLE_DEACTIVATION, DISABLE_SIMULATION, ISLAND_SLEEPING, WANTS_DEACTIVATION
 
Constructor Summary
RigidBody(float mass, MotionState motionState, CollisionShape collisionShape)
           
RigidBody(float mass, MotionState motionState, CollisionShape collisionShape, Vector3f localInertia)
           
RigidBody(RigidBodyConstructionInfo constructionInfo)
           
 
Method Summary
 void addConstraintRef(TypedConstraint c)
           
 void applyCentralForce(Vector3f force)
           
 void applyCentralImpulse(Vector3f impulse)
           
 void applyDamping(float timeStep)
          Damps the velocity, using the given linearDamping and angularDamping.
 void applyForce(Vector3f force, Vector3f rel_pos)
           
 void applyGravity()
           
 void applyImpulse(Vector3f impulse, Vector3f rel_pos)
           
 void applyTorque(Vector3f torque)
           
 void applyTorqueImpulse(Vector3f torque)
           
 void clearForces()
           
 float computeAngularImpulseDenominator(Vector3f axis)
           
 float computeImpulseDenominator(Vector3f pos, Vector3f normal)
           
 void destroy()
           
 void getAabb(Vector3f aabbMin, Vector3f aabbMax)
           
 float getAngularDamping()
           
 float getAngularFactor()
           
 float getAngularSleepingThreshold()
           
 Vector3f getAngularVelocity(Vector3f out)
           
 BroadphaseProxy getBroadphaseProxy()
           
 Vector3f getCenterOfMassPosition(Vector3f out)
           
 Transform getCenterOfMassTransform(Transform out)
           
 TypedConstraint getConstraintRef(int index)
           
 Vector3f getGravity(Vector3f out)
           
 Vector3f getInvInertiaDiagLocal(Vector3f out)
           
 Matrix3f getInvInertiaTensorWorld(Matrix3f out)
           
 float getInvMass()
           
 float getLinearDamping()
           
 float getLinearSleepingThreshold()
           
 Vector3f getLinearVelocity(Vector3f out)
           
 MotionState getMotionState()
           
 int getNumConstraintRefs()
           
 Quat4f getOrientation(Quat4f out)
           
 Vector3f getVelocityInLocalPoint(Vector3f rel_pos, Vector3f out)
           
 boolean checkCollideWithOverride(CollisionObject co)
           
 void integrateVelocities(float step)
           
 void internalApplyImpulse(Vector3f linearComponent, Vector3f angularComponent, float impulseMagnitude)
          Optimization for the iterative solver: avoid calculating constant terms involving inertia, normal, relative position.
 boolean isInWorld()
          Is this rigidbody added to a CollisionWorld/DynamicsWorld/Broadphase?
 void predictIntegratedTransform(float timeStep, Transform predictedTransform)
          Continuous collision detection needs prediction.
 void proceedToTransform(Transform newTrans)
           
 void removeConstraintRef(TypedConstraint c)
           
 void saveKinematicState(float timeStep)
           
 void setAngularFactor(float angFac)
           
 void setAngularVelocity(Vector3f ang_vel)
           
 void setCenterOfMassTransform(Transform xform)
           
 void setDamping(float lin_damping, float ang_damping)
           
 void setGravity(Vector3f acceleration)
           
 void setInvInertiaDiagLocal(Vector3f diagInvInertia)
           
 void setLinearVelocity(Vector3f lin_vel)
           
 void setMassProps(float mass, Vector3f inertia)
           
 void setMotionState(MotionState motionState)
           
 void setNewBroadphaseProxy(BroadphaseProxy broadphaseProxy)
           
 void setSleepingThresholds(float linear, float angular)
           
 void translate(Vector3f v)
           
static RigidBody upcast(CollisionObject colObj)
          To keep collision detection and dynamics separate we don't store a rigidbody pointer, but a rigidbody is derived from CollisionObject, so we can safely perform an upcast.
 void updateDeactivation(float timeStep)
           
 void updateInertiaTensor()
           
 boolean wantsSleeping()
           
 
Methods inherited from class com.bulletphysics.collision.dispatch.CollisionObject
activate, activate, forceActivationState, getActivationState, getBroadphaseHandle, getCcdMotionThreshold, getCcdSquareMotionThreshold, getCcdSweptSphereRadius, getCollisionFlags, getCollisionShape, getCompanionId, getDeactivationTime, getFriction, getHitFraction, getInternalType, getInterpolationAngularVelocity, getInterpolationLinearVelocity, getInterpolationWorldTransform, getIslandTag, getRestitution, getRootCollisionShape, getUserPointer, getWorldTransform, hasContactResponse, checkCollideWith, internalSetTemporaryCollisionShape, isActive, isKinematicObject, isStaticObject, isStaticOrKinematicObject, mergesSimulationIslands, setActivationState, setBroadphaseHandle, setCcdMotionThreshold, setCcdSweptSphereRadius, setCollisionFlags, setCollisionShape, setCompanionId, setDeactivationTime, setFriction, setHitFraction, setInterpolationAngularVelocity, setInterpolationLinearVelocity, setInterpolationWorldTransform, setIslandTag, setRestitution, setUserPointer, setWorldTransform
 
Methods inherited from class java.lang.Object
equals, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
 

Field Detail

contactSolverType

public int contactSolverType

frictionSolverType

public int frictionSolverType

debugBodyId

public int debugBodyId
Constructor Detail

RigidBody

public RigidBody(RigidBodyConstructionInfo constructionInfo)

RigidBody

public RigidBody(float mass,
                 MotionState motionState,
                 CollisionShape collisionShape)

RigidBody

public RigidBody(float mass,
                 MotionState motionState,
                 CollisionShape collisionShape,
                 Vector3f localInertia)
Method Detail

destroy

public void destroy()

proceedToTransform

public void proceedToTransform(Transform newTrans)

upcast

public static RigidBody upcast(CollisionObject colObj)
To keep collision detection and dynamics separate we don't store a rigidbody pointer, but a rigidbody is derived from CollisionObject, so we can safely perform an upcast.


predictIntegratedTransform

public void predictIntegratedTransform(float timeStep,
                                       Transform predictedTransform)
Continuous collision detection needs prediction.


saveKinematicState

public void saveKinematicState(float timeStep)

applyGravity

public void applyGravity()

setGravity

public void setGravity(Vector3f acceleration)

getGravity

public Vector3f getGravity(Vector3f out)

setDamping

public void setDamping(float lin_damping,
                       float ang_damping)

getLinearDamping

public float getLinearDamping()

getAngularDamping

public float getAngularDamping()

getLinearSleepingThreshold

public float getLinearSleepingThreshold()

getAngularSleepingThreshold

public float getAngularSleepingThreshold()

applyDamping

public void applyDamping(float timeStep)
Damps the velocity, using the given linearDamping and angularDamping.


setMassProps

public void setMassProps(float mass,
                         Vector3f inertia)

getInvMass

public float getInvMass()

getInvInertiaTensorWorld

public Matrix3f getInvInertiaTensorWorld(Matrix3f out)

integrateVelocities

public void integrateVelocities(float step)

setCenterOfMassTransform

public void setCenterOfMassTransform(Transform xform)

applyCentralForce

public void applyCentralForce(Vector3f force)

getInvInertiaDiagLocal

public Vector3f getInvInertiaDiagLocal(Vector3f out)

setInvInertiaDiagLocal

public void setInvInertiaDiagLocal(Vector3f diagInvInertia)

setSleepingThresholds

public void setSleepingThresholds(float linear,
                                  float angular)

applyTorque

public void applyTorque(Vector3f torque)

applyForce

public void applyForce(Vector3f force,
                       Vector3f rel_pos)

applyCentralImpulse

public void applyCentralImpulse(Vector3f impulse)

applyTorqueImpulse

public void applyTorqueImpulse(Vector3f torque)

applyImpulse

public void applyImpulse(Vector3f impulse,
                         Vector3f rel_pos)

internalApplyImpulse

public void internalApplyImpulse(Vector3f linearComponent,
                                 Vector3f angularComponent,
                                 float impulseMagnitude)
Optimization for the iterative solver: avoid calculating constant terms involving inertia, normal, relative position.


clearForces

public void clearForces()

updateInertiaTensor

public void updateInertiaTensor()

getCenterOfMassPosition

public Vector3f getCenterOfMassPosition(Vector3f out)

getOrientation

public Quat4f getOrientation(Quat4f out)

getCenterOfMassTransform

public Transform getCenterOfMassTransform(Transform out)

getLinearVelocity

public Vector3f getLinearVelocity(Vector3f out)

getAngularVelocity

public Vector3f getAngularVelocity(Vector3f out)

setLinearVelocity

public void setLinearVelocity(Vector3f lin_vel)

setAngularVelocity

public void setAngularVelocity(Vector3f ang_vel)

getVelocityInLocalPoint

public Vector3f getVelocityInLocalPoint(Vector3f rel_pos,
                                        Vector3f out)

translate

public void translate(Vector3f v)

getAabb

public void getAabb(Vector3f aabbMin,
                    Vector3f aabbMax)

computeImpulseDenominator

public float computeImpulseDenominator(Vector3f pos,
                                       Vector3f normal)

computeAngularImpulseDenominator

public float computeAngularImpulseDenominator(Vector3f axis)

updateDeactivation

public void updateDeactivation(float timeStep)

wantsSleeping

public boolean wantsSleeping()

getBroadphaseProxy

public BroadphaseProxy getBroadphaseProxy()

setNewBroadphaseProxy

public void setNewBroadphaseProxy(BroadphaseProxy broadphaseProxy)

getMotionState

public MotionState getMotionState()

setMotionState

public void setMotionState(MotionState motionState)

setAngularFactor

public void setAngularFactor(float angFac)

getAngularFactor

public float getAngularFactor()

isInWorld

public boolean isInWorld()
Is this rigidbody added to a CollisionWorld/DynamicsWorld/Broadphase?


checkCollideWithOverride

public boolean checkCollideWithOverride(CollisionObject co)
Overrides:
checkCollideWithOverride in class CollisionObject

addConstraintRef

public void addConstraintRef(TypedConstraint c)

removeConstraintRef

public void removeConstraintRef(TypedConstraint c)

getConstraintRef

public TypedConstraint getConstraintRef(int index)

getNumConstraintRefs

public int getNumConstraintRefs()