com.bulletphysics.dynamics.constraintsolver
Class SliderConstraint

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

public class SliderConstraint
extends TypedConstraint


Field Summary
static float SLIDER_CONSTRAINT_DEF_DAMPING
           
static float SLIDER_CONSTRAINT_DEF_RESTITUTION
           
static float SLIDER_CONSTRAINT_DEF_SOFTNESS
           
 
Constructor Summary
SliderConstraint()
           
SliderConstraint(RigidBody rbA, RigidBody rbB, Transform frameInA, Transform frameInB, boolean useLinearReferenceFrameA)
           
 
Method Summary
 void buildJacobian()
           
 void buildJacobianInt(RigidBody rbA, RigidBody rbB, Transform frameInA, Transform frameInB)
           
 void calculateTransforms()
           
 Vector3f getAncorInA(Vector3f out)
           
 Vector3f getAncorInB(Vector3f out)
           
 float getAngDepth()
           
 Transform getCalculatedTransformA(Transform out)
           
 Transform getCalculatedTransformB(Transform out)
           
 float getDampingDirAng()
           
 float getDampingDirLin()
           
 float getDampingLimAng()
           
 float getDampingLimLin()
           
 float getDampingOrthoAng()
           
 float getDampingOrthoLin()
           
 Transform getFrameOffsetA(Transform out)
           
 Transform getFrameOffsetB(Transform out)
           
 float getLinDepth()
           
 float getLinearPos()
           
 float getLowerAngLimit()
           
 float getLowerLinLimit()
           
 float getMaxAngMotorForce()
           
 float getMaxLinMotorForce()
           
 boolean getPoweredAngMotor()
           
 boolean getPoweredLinMotor()
           
 float getRestitutionDirAng()
           
 float getRestitutionDirLin()
           
 float getRestitutionLimAng()
           
 float getRestitutionLimLin()
           
 float getRestitutionOrthoAng()
           
 float getRestitutionOrthoLin()
           
 float getSoftnessDirAng()
           
 float getSoftnessDirLin()
           
 float getSoftnessLimAng()
           
 float getSoftnessLimLin()
           
 float getSoftnessOrthoAng()
           
 float getSoftnessOrthoLin()
           
 boolean getSolveAngLimit()
           
 boolean getSolveLinLimit()
           
 float getTargetAngMotorVelocity()
           
 float getTargetLinMotorVelocity()
           
 float getUpperAngLimit()
           
 float getUpperLinLimit()
           
 boolean getUseLinearReferenceFrameA()
           
 void setDampingDirAng(float dampingDirAng)
           
 void setDampingDirLin(float dampingDirLin)
           
 void setDampingLimAng(float dampingLimAng)
           
 void setDampingLimLin(float dampingLimLin)
           
 void setDampingOrthoAng(float dampingOrthoAng)
           
 void setDampingOrthoLin(float dampingOrthoLin)
           
 void setLowerAngLimit(float lowerLimit)
           
 void setLowerLinLimit(float lowerLimit)
           
 void setMaxAngMotorForce(float maxAngMotorForce)
           
 void setMaxLinMotorForce(float maxLinMotorForce)
           
 void setPoweredAngMotor(boolean onOff)
           
 void setPoweredLinMotor(boolean onOff)
           
 void setRestitutionDirAng(float restitutionDirAng)
           
 void setRestitutionDirLin(float restitutionDirLin)
           
 void setRestitutionLimAng(float restitutionLimAng)
           
 void setRestitutionLimLin(float restitutionLimLin)
           
 void setRestitutionOrthoAng(float restitutionOrthoAng)
           
 void setRestitutionOrthoLin(float restitutionOrthoLin)
           
 void setSoftnessDirAng(float softnessDirAng)
           
 void setSoftnessDirLin(float softnessDirLin)
           
 void setSoftnessLimAng(float softnessLimAng)
           
 void setSoftnessLimLin(float softnessLimLin)
           
 void setSoftnessOrthoAng(float softnessOrthoAng)
           
 void setSoftnessOrthoLin(float softnessOrthoLin)
           
 void setTargetAngMotorVelocity(float targetAngMotorVelocity)
           
 void setTargetLinMotorVelocity(float targetLinMotorVelocity)
           
 void setUpperAngLimit(float upperLimit)
           
 void setUpperLinLimit(float upperLimit)
           
 void solveConstraint(float timeStep)
           
 void solveConstraintInt(RigidBody rbA, RigidBody rbB)
           
 void testAngLimits()
           
 void testLinLimits()
           
 
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
 

Field Detail

SLIDER_CONSTRAINT_DEF_SOFTNESS

public static final float SLIDER_CONSTRAINT_DEF_SOFTNESS
See Also:
Constant Field Values

SLIDER_CONSTRAINT_DEF_DAMPING

public static final float SLIDER_CONSTRAINT_DEF_DAMPING
See Also:
Constant Field Values

SLIDER_CONSTRAINT_DEF_RESTITUTION

public static final float SLIDER_CONSTRAINT_DEF_RESTITUTION
See Also:
Constant Field Values
Constructor Detail

SliderConstraint

public SliderConstraint()

SliderConstraint

public SliderConstraint(RigidBody rbA,
                        RigidBody rbB,
                        Transform frameInA,
                        Transform frameInB,
                        boolean useLinearReferenceFrameA)
Method Detail

buildJacobian

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

solveConstraint

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

getCalculatedTransformA

public Transform getCalculatedTransformA(Transform out)

getCalculatedTransformB

public Transform getCalculatedTransformB(Transform out)

getFrameOffsetA

public Transform getFrameOffsetA(Transform out)

getFrameOffsetB

public Transform getFrameOffsetB(Transform out)

getLowerLinLimit

public float getLowerLinLimit()

setLowerLinLimit

public void setLowerLinLimit(float lowerLimit)

getUpperLinLimit

public float getUpperLinLimit()

setUpperLinLimit

public void setUpperLinLimit(float upperLimit)

getLowerAngLimit

public float getLowerAngLimit()

setLowerAngLimit

public void setLowerAngLimit(float lowerLimit)

getUpperAngLimit

public float getUpperAngLimit()

setUpperAngLimit

public void setUpperAngLimit(float upperLimit)

getUseLinearReferenceFrameA

public boolean getUseLinearReferenceFrameA()

getSoftnessDirLin

public float getSoftnessDirLin()

getRestitutionDirLin

public float getRestitutionDirLin()

getDampingDirLin

public float getDampingDirLin()

getSoftnessDirAng

public float getSoftnessDirAng()

getRestitutionDirAng

public float getRestitutionDirAng()

getDampingDirAng

public float getDampingDirAng()

getSoftnessLimLin

public float getSoftnessLimLin()

getRestitutionLimLin

public float getRestitutionLimLin()

getDampingLimLin

public float getDampingLimLin()

getSoftnessLimAng

public float getSoftnessLimAng()

getRestitutionLimAng

public float getRestitutionLimAng()

getDampingLimAng

public float getDampingLimAng()

getSoftnessOrthoLin

public float getSoftnessOrthoLin()

getRestitutionOrthoLin

public float getRestitutionOrthoLin()

getDampingOrthoLin

public float getDampingOrthoLin()

getSoftnessOrthoAng

public float getSoftnessOrthoAng()

getRestitutionOrthoAng

public float getRestitutionOrthoAng()

getDampingOrthoAng

public float getDampingOrthoAng()

setSoftnessDirLin

public void setSoftnessDirLin(float softnessDirLin)

setRestitutionDirLin

public void setRestitutionDirLin(float restitutionDirLin)

setDampingDirLin

public void setDampingDirLin(float dampingDirLin)

setSoftnessDirAng

public void setSoftnessDirAng(float softnessDirAng)

setRestitutionDirAng

public void setRestitutionDirAng(float restitutionDirAng)

setDampingDirAng

public void setDampingDirAng(float dampingDirAng)

setSoftnessLimLin

public void setSoftnessLimLin(float softnessLimLin)

setRestitutionLimLin

public void setRestitutionLimLin(float restitutionLimLin)

setDampingLimLin

public void setDampingLimLin(float dampingLimLin)

setSoftnessLimAng

public void setSoftnessLimAng(float softnessLimAng)

setRestitutionLimAng

public void setRestitutionLimAng(float restitutionLimAng)

setDampingLimAng

public void setDampingLimAng(float dampingLimAng)

setSoftnessOrthoLin

public void setSoftnessOrthoLin(float softnessOrthoLin)

setRestitutionOrthoLin

public void setRestitutionOrthoLin(float restitutionOrthoLin)

setDampingOrthoLin

public void setDampingOrthoLin(float dampingOrthoLin)

setSoftnessOrthoAng

public void setSoftnessOrthoAng(float softnessOrthoAng)

setRestitutionOrthoAng

public void setRestitutionOrthoAng(float restitutionOrthoAng)

setDampingOrthoAng

public void setDampingOrthoAng(float dampingOrthoAng)

setPoweredLinMotor

public void setPoweredLinMotor(boolean onOff)

getPoweredLinMotor

public boolean getPoweredLinMotor()

setTargetLinMotorVelocity

public void setTargetLinMotorVelocity(float targetLinMotorVelocity)

getTargetLinMotorVelocity

public float getTargetLinMotorVelocity()

setMaxLinMotorForce

public void setMaxLinMotorForce(float maxLinMotorForce)

getMaxLinMotorForce

public float getMaxLinMotorForce()

setPoweredAngMotor

public void setPoweredAngMotor(boolean onOff)

getPoweredAngMotor

public boolean getPoweredAngMotor()

setTargetAngMotorVelocity

public void setTargetAngMotorVelocity(float targetAngMotorVelocity)

getTargetAngMotorVelocity

public float getTargetAngMotorVelocity()

setMaxAngMotorForce

public void setMaxAngMotorForce(float maxAngMotorForce)

getMaxAngMotorForce

public float getMaxAngMotorForce()

getLinearPos

public float getLinearPos()

getSolveLinLimit

public boolean getSolveLinLimit()

getLinDepth

public float getLinDepth()

getSolveAngLimit

public boolean getSolveAngLimit()

getAngDepth

public float getAngDepth()

buildJacobianInt

public void buildJacobianInt(RigidBody rbA,
                             RigidBody rbB,
                             Transform frameInA,
                             Transform frameInB)

solveConstraintInt

public void solveConstraintInt(RigidBody rbA,
                               RigidBody rbB)

calculateTransforms

public void calculateTransforms()

testLinLimits

public void testLinLimits()

testAngLimits

public void testAngLimits()

getAncorInA

public Vector3f getAncorInA(Vector3f out)

getAncorInB

public Vector3f getAncorInB(Vector3f out)