com.bulletphysics.dynamics.constraintsolver
Class HingeConstraint

java.lang.Object
  extended by com.bulletphysics.dynamics.constraintsolver.TypedConstraint
      extended by com.bulletphysics.dynamics.constraintsolver.HingeConstraint

public class HingeConstraint
extends TypedConstraint

Hinge constraint between two rigid bodies each with a pivot point that descibes the axis location in local space. Axis defines the orientation of the hinge axis.


Constructor Summary
HingeConstraint()
           
HingeConstraint(RigidBody rbA, RigidBody rbB, Transform rbAFrame, Transform rbBFrame)
           
HingeConstraint(RigidBody rbA, RigidBody rbB, Vector3f pivotInA, Vector3f pivotInB, Vector3f axisInA, Vector3f axisInB)
           
HingeConstraint(RigidBody rbA, Transform rbAFrame)
           
HingeConstraint(RigidBody rbA, Vector3f pivotInA, Vector3f axisInA)
           
 
Method Summary
 void buildJacobian()
           
 void enableAngularMotor(boolean enableMotor, float targetVelocity, float maxMotorImpulse)
           
 Transform getAFrame(Transform out)
           
 boolean getAngularOnly()
           
 Transform getBFrame(Transform out)
           
 boolean getEnableAngularMotor()
           
 float getHingeAngle()
           
 float getLimitSign()
           
 float getLowerLimit()
           
 float getMaxMotorImpulse()
           
 float getMotorTargetVelosity()
           
 boolean getSolveLimit()
           
 float getUpperLimit()
           
 void setAngularOnly(boolean angularOnly)
           
 void setLimit(float low, float high)
           
 void setLimit(float low, float high, float _softness, float _biasFactor, float _relaxationFactor)
           
 void solveConstraint(float timeStep)
           
 void updateRHS(float timeStep)
           
 
Methods inherited from class com.bulletphysics.dynamics.constraintsolver.TypedConstraint
getAppliedImpulse, getConstraintType, getRigidBodyA, getRigidBodyB, getUid, getUserConstraintId, getUserConstraintType, setUserConstraintId, setUserConstraintType
 
Methods inherited from class java.lang.Object
equals, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
 

Constructor Detail

HingeConstraint

public HingeConstraint()

HingeConstraint

public HingeConstraint(RigidBody rbA,
                       RigidBody rbB,
                       Vector3f pivotInA,
                       Vector3f pivotInB,
                       Vector3f axisInA,
                       Vector3f axisInB)

HingeConstraint

public HingeConstraint(RigidBody rbA,
                       Vector3f pivotInA,
                       Vector3f axisInA)

HingeConstraint

public HingeConstraint(RigidBody rbA,
                       RigidBody rbB,
                       Transform rbAFrame,
                       Transform rbBFrame)

HingeConstraint

public HingeConstraint(RigidBody rbA,
                       Transform rbAFrame)
Method Detail

buildJacobian

public void buildJacobian()
Specified by:
buildJacobian in class TypedConstraint

solveConstraint

public void solveConstraint(float timeStep)
Specified by:
solveConstraint in class TypedConstraint

updateRHS

public void updateRHS(float timeStep)

getHingeAngle

public float getHingeAngle()

setAngularOnly

public void setAngularOnly(boolean angularOnly)

enableAngularMotor

public void enableAngularMotor(boolean enableMotor,
                               float targetVelocity,
                               float maxMotorImpulse)

setLimit

public void setLimit(float low,
                     float high)

setLimit

public void setLimit(float low,
                     float high,
                     float _softness,
                     float _biasFactor,
                     float _relaxationFactor)

getLowerLimit

public float getLowerLimit()

getUpperLimit

public float getUpperLimit()

getAFrame

public Transform getAFrame(Transform out)

getBFrame

public Transform getBFrame(Transform out)

getSolveLimit

public boolean getSolveLimit()

getLimitSign

public float getLimitSign()

getAngularOnly

public boolean getAngularOnly()

getEnableAngularMotor

public boolean getEnableAngularMotor()

getMotorTargetVelosity

public float getMotorTargetVelosity()

getMaxMotorImpulse

public float getMaxMotorImpulse()