btGeneric6DofConstraint between two rigidbodies each with a pivotpoint that descibes the axis location in local space More...
#include <btGeneric6DofConstraint.h>
Public Member Functions | |
btGeneric6DofConstraint (btRigidBody &rbA, btRigidBody &rbB, const btTransform &frameInA, const btTransform &frameInB, bool useLinearReferenceFrameA) | |
btGeneric6DofConstraint (btRigidBody &rbB, const btTransform &frameInB, bool useLinearReferenceFrameB) | |
virtual void | buildJacobian () |
performs Jacobian calculation, and also calculates angle differences and axis | |
virtual void | calcAnchorPos (void) |
virtual int | calculateSerializeBufferSize () const |
void | calculateTransforms (const btTransform &transA, const btTransform &transB) |
Calcs global transform of the offsets. | |
void | calculateTransforms () |
int | get_limit_motor_info2 (btRotationalLimitMotor *limot, const btTransform &transA, const btTransform &transB, const btVector3 &linVelA, const btVector3 &linVelB, const btVector3 &angVelA, const btVector3 &angVelB, btConstraintInfo2 *info, int row, btVector3 &ax1, int rotational, int rotAllowed=false) |
btScalar | getAngle (int axis_index) const |
Get the relative Euler angle. | |
void | getAngularLowerLimit (btVector3 &angularLower) |
void | getAngularUpperLimit (btVector3 &angularUpper) |
btVector3 | getAxis (int axis_index) const |
Get the rotation axis in global coordinates. | |
const btTransform & | getCalculatedTransformA () const |
Gets the global transform of the offset for body A. | |
const btTransform & | getCalculatedTransformB () const |
Gets the global transform of the offset for body B. | |
const btTransform & | getFrameOffsetA () const |
btTransform & | getFrameOffsetA () |
const btTransform & | getFrameOffsetB () const |
btTransform & | getFrameOffsetB () |
virtual void | getInfo1 (btConstraintInfo1 *info) |
internal method used by the constraint solver, don't use them directly | |
void | getInfo1NonVirtual (btConstraintInfo1 *info) |
virtual void | getInfo2 (btConstraintInfo2 *info) |
internal method used by the constraint solver, don't use them directly | |
void | getInfo2NonVirtual (btConstraintInfo2 *info, const btTransform &transA, const btTransform &transB, const btVector3 &linVelA, const btVector3 &linVelB, const btVector3 &angVelA, const btVector3 &angVelB) |
void | getLinearLowerLimit (btVector3 &linearLower) |
void | getLinearUpperLimit (btVector3 &linearUpper) |
virtual btScalar | getParam (int num, int axis=-1) const |
return the local value of parameter | |
btScalar | getRelativePivotPosition (int axis_index) const |
Get the relative position of the constraint pivot. | |
btRotationalLimitMotor * | getRotationalLimitMotor (int index) |
Retrieves the angular limit informacion. | |
btTranslationalLimitMotor * | getTranslationalLimitMotor () |
Retrieves the limit informacion. | |
bool | getUseFrameOffset () |
bool | isLimited (int limitIndex) |
Test limit. | |
virtual const char * | serialize (void *dataBuffer, btSerializer *serializer) const |
fills the dataBuffer and returns the struct name (and 0 on failure) | |
void | setAngularLowerLimit (const btVector3 &angularLower) |
void | setAngularUpperLimit (const btVector3 &angularUpper) |
void | setAxis (const btVector3 &axis1, const btVector3 &axis2) |
void | setFrames (const btTransform &frameA, const btTransform &frameB) |
void | setLimit (int axis, btScalar lo, btScalar hi) |
void | setLinearLowerLimit (const btVector3 &linearLower) |
void | setLinearUpperLimit (const btVector3 &linearUpper) |
virtual void | setParam (int num, btScalar value, int axis=-1) |
void | setUseFrameOffset (bool frameOffsetOnOff) |
bool | testAngularLimitMotor (int axis_index) |
Test angular limit. | |
void | updateRHS (btScalar timeStep) |
Public Attributes | |
bool | m_useSolveConstraintObsolete |
for backwards compatibility during the transition to 'getInfo/getInfo2' | |
Protected Member Functions | |
void | buildAngularJacobian (btJacobianEntry &jacAngular, const btVector3 &jointAxisW) |
void | buildLinearJacobian (btJacobianEntry &jacLinear, const btVector3 &normalWorld, const btVector3 &pivotAInW, const btVector3 &pivotBInW) |
void | calculateAngleInfo () |
calcs the euler angles between the two bodies. | |
void | calculateLinearInfo () |
btGeneric6DofConstraint & | operator= (btGeneric6DofConstraint &other) |
int | setAngularLimits (btConstraintInfo2 *info, int row_offset, const btTransform &transA, const btTransform &transB, const btVector3 &linVelA, const btVector3 &linVelB, const btVector3 &angVelA, const btVector3 &angVelB) |
int | setLinearLimits (btConstraintInfo2 *info, int row, const btTransform &transA, const btTransform &transB, const btVector3 &linVelA, const btVector3 &linVelB, const btVector3 &angVelA, const btVector3 &angVelB) |
Protected Attributes | |
btTransform | m_frameInA |
the constraint space w.r.t body A | |
btTransform | m_frameInB |
btJacobianEntry | m_jacLinear [3] |
3 orthogonal linear constraints | |
btJacobianEntry | m_jacAng [3] |
btTranslationalLimitMotor | m_linearLimits |
btRotationalLimitMotor | m_angularLimits [3] |
btScalar | m_timeStep |
btTransform | m_calculatedTransformA |
btTransform | m_calculatedTransformB |
btVector3 | m_calculatedAxisAngleDiff |
btVector3 | m_calculatedAxis [3] |
btVector3 | m_calculatedLinearDiff |
btScalar | m_factA |
btScalar | m_factB |
bool | m_hasStaticBody |
btVector3 | m_AnchorPos |
bool | m_useLinearReferenceFrameA |
bool | m_useOffsetForConstraintFrame |
int | m_flags |
btGeneric6DofConstraint between two rigidbodies each with a pivotpoint that descibes the axis location in local space
btGeneric6DofConstraint can leave any of the 6 degree of freedom 'free' or 'locked'. currently this limit supports rotational motors
For Linear limits, use btGeneric6DofConstraint.setLinearUpperLimit, btGeneric6DofConstraint.setLinearLowerLimit. You can set the parameters with the btTranslationalLimitMotor structure accsesible through the btGeneric6DofConstraint.getTranslationalLimitMotor method. At this moment translational motors are not supported. May be in the future.
For Angular limits, use the btRotationalLimitMotor structure for configuring the limit. This is accessible through btGeneric6DofConstraint.getLimitMotor method, This brings support for limit parameters and motors.
AXIS | MIN ANGLE | MAX ANGLE |
X | -PI | PI |
Y | -PI/2 | PI/2 |
Z | -PI | PI |
Definition at line 271 of file btGeneric6DofConstraint.h.
btGeneric6DofConstraint::btGeneric6DofConstraint | ( | btRigidBody & | rbA, |
btRigidBody & | rbB, | ||
const btTransform & | frameInA, | ||
const btTransform & | frameInB, | ||
bool | useLinearReferenceFrameA | ||
) |
btGeneric6DofConstraint::btGeneric6DofConstraint | ( | btRigidBody & | rbB, |
const btTransform & | frameInB, | ||
bool | useLinearReferenceFrameB | ||
) |
void btGeneric6DofConstraint::buildAngularJacobian | ( | btJacobianEntry & | jacAngular, |
const btVector3 & | jointAxisW | ||
) | [protected] |
virtual void btGeneric6DofConstraint::buildJacobian | ( | ) | [virtual] |
performs Jacobian calculation, and also calculates angle differences and axis
Reimplemented from btTypedConstraint.
void btGeneric6DofConstraint::buildLinearJacobian | ( | btJacobianEntry & | jacLinear, |
const btVector3 & | normalWorld, | ||
const btVector3 & | pivotAInW, | ||
const btVector3 & | pivotBInW | ||
) | [protected] |
virtual void btGeneric6DofConstraint::calcAnchorPos | ( | void | ) | [virtual] |
void btGeneric6DofConstraint::calculateAngleInfo | ( | ) | [protected] |
calcs the euler angles between the two bodies.
void btGeneric6DofConstraint::calculateLinearInfo | ( | ) | [protected] |
SIMD_FORCE_INLINE int btGeneric6DofConstraint::calculateSerializeBufferSize | ( | ) | const [virtual] |
Reimplemented from btTypedConstraint.
Reimplemented in btGeneric6DofSpringConstraint.
Definition at line 579 of file btGeneric6DofConstraint.h.
void btGeneric6DofConstraint::calculateTransforms | ( | const btTransform & | transA, |
const btTransform & | transB | ||
) |
Calcs global transform of the offsets.
Calcs the global transform for the joint offset for body A an B, and also calcs the agle differences between the bodies.
int btGeneric6DofConstraint::get_limit_motor_info2 | ( | btRotationalLimitMotor * | limot, |
const btTransform & | transA, | ||
const btTransform & | transB, | ||
const btVector3 & | linVelA, | ||
const btVector3 & | linVelB, | ||
const btVector3 & | angVelA, | ||
const btVector3 & | angVelB, | ||
btConstraintInfo2 * | info, | ||
int | row, | ||
btVector3 & | ax1, | ||
int | rotational, | ||
int | rotAllowed = false |
||
) |
btScalar btGeneric6DofConstraint::getAngle | ( | int | axis_index | ) | const |
Get the relative Euler angle.
void btGeneric6DofConstraint::getAngularLowerLimit | ( | btVector3 & | angularLower | ) | [inline] |
Definition at line 471 of file btGeneric6DofConstraint.h.
void btGeneric6DofConstraint::getAngularUpperLimit | ( | btVector3 & | angularUpper | ) | [inline] |
Definition at line 483 of file btGeneric6DofConstraint.h.
btVector3 btGeneric6DofConstraint::getAxis | ( | int | axis_index | ) | const |
Get the rotation axis in global coordinates.
const btTransform& btGeneric6DofConstraint::getCalculatedTransformA | ( | ) | const [inline] |
Gets the global transform of the offset for body A.
Definition at line 368 of file btGeneric6DofConstraint.h.
const btTransform& btGeneric6DofConstraint::getCalculatedTransformB | ( | ) | const [inline] |
Gets the global transform of the offset for body B.
Definition at line 377 of file btGeneric6DofConstraint.h.
const btTransform& btGeneric6DofConstraint::getFrameOffsetA | ( | ) | const [inline] |
Definition at line 382 of file btGeneric6DofConstraint.h.
btTransform& btGeneric6DofConstraint::getFrameOffsetA | ( | ) | [inline] |
Definition at line 393 of file btGeneric6DofConstraint.h.
const btTransform& btGeneric6DofConstraint::getFrameOffsetB | ( | ) | const [inline] |
Definition at line 387 of file btGeneric6DofConstraint.h.
btTransform& btGeneric6DofConstraint::getFrameOffsetB | ( | ) | [inline] |
Definition at line 398 of file btGeneric6DofConstraint.h.
virtual void btGeneric6DofConstraint::getInfo1 | ( | btConstraintInfo1 * | info | ) | [virtual] |
internal method used by the constraint solver, don't use them directly
Implements btTypedConstraint.
void btGeneric6DofConstraint::getInfo1NonVirtual | ( | btConstraintInfo1 * | info | ) |
virtual void btGeneric6DofConstraint::getInfo2 | ( | btConstraintInfo2 * | info | ) | [virtual] |
internal method used by the constraint solver, don't use them directly
Implements btTypedConstraint.
Reimplemented in btGeneric6DofSpringConstraint.
void btGeneric6DofConstraint::getInfo2NonVirtual | ( | btConstraintInfo2 * | info, |
const btTransform & | transA, | ||
const btTransform & | transB, | ||
const btVector3 & | linVelA, | ||
const btVector3 & | linVelB, | ||
const btVector3 & | angVelA, | ||
const btVector3 & | angVelB | ||
) |
void btGeneric6DofConstraint::getLinearLowerLimit | ( | btVector3 & | linearLower | ) | [inline] |
Definition at line 450 of file btGeneric6DofConstraint.h.
void btGeneric6DofConstraint::getLinearUpperLimit | ( | btVector3 & | linearUpper | ) | [inline] |
Definition at line 460 of file btGeneric6DofConstraint.h.
virtual btScalar btGeneric6DofConstraint::getParam | ( | int | num, |
int | axis = -1 |
||
) | const [virtual] |
return the local value of parameter
Implements btTypedConstraint.
btScalar btGeneric6DofConstraint::getRelativePivotPosition | ( | int | axis_index | ) | const |
Get the relative position of the constraint pivot.
btRotationalLimitMotor* btGeneric6DofConstraint::getRotationalLimitMotor | ( | int | index | ) | [inline] |
Retrieves the angular limit informacion.
Definition at line 490 of file btGeneric6DofConstraint.h.
Retrieves the limit informacion.
Definition at line 496 of file btGeneric6DofConstraint.h.
bool btGeneric6DofConstraint::getUseFrameOffset | ( | ) | [inline] |
Definition at line 542 of file btGeneric6DofConstraint.h.
bool btGeneric6DofConstraint::isLimited | ( | int | limitIndex | ) | [inline] |
Test limit.
Definition at line 525 of file btGeneric6DofConstraint.h.
btGeneric6DofConstraint& btGeneric6DofConstraint::operator= | ( | btGeneric6DofConstraint & | other | ) | [inline, protected] |
Definition at line 321 of file btGeneric6DofConstraint.h.
SIMD_FORCE_INLINE const char * btGeneric6DofConstraint::serialize | ( | void * | dataBuffer, |
btSerializer * | serializer | ||
) | const [virtual] |
fills the dataBuffer and returns the struct name (and 0 on failure)
Reimplemented from btTypedConstraint.
Reimplemented in btGeneric6DofSpringConstraint.
Definition at line 585 of file btGeneric6DofConstraint.h.
int btGeneric6DofConstraint::setAngularLimits | ( | btConstraintInfo2 * | info, |
int | row_offset, | ||
const btTransform & | transA, | ||
const btTransform & | transB, | ||
const btVector3 & | linVelA, | ||
const btVector3 & | linVelB, | ||
const btVector3 & | angVelA, | ||
const btVector3 & | angVelB | ||
) | [protected] |
void btGeneric6DofConstraint::setAngularLowerLimit | ( | const btVector3 & | angularLower | ) | [inline] |
Definition at line 465 of file btGeneric6DofConstraint.h.
void btGeneric6DofConstraint::setAngularUpperLimit | ( | const btVector3 & | angularUpper | ) | [inline] |
Definition at line 477 of file btGeneric6DofConstraint.h.
void btGeneric6DofConstraint::setAxis | ( | const btVector3 & | axis1, |
const btVector3 & | axis2 | ||
) |
Reimplemented in btUniversalConstraint, and btGeneric6DofSpringConstraint.
void btGeneric6DofConstraint::setFrames | ( | const btTransform & | frameA, |
const btTransform & | frameB | ||
) |
void btGeneric6DofConstraint::setLimit | ( | int | axis, |
btScalar | lo, | ||
btScalar | hi | ||
) | [inline] |
Definition at line 502 of file btGeneric6DofConstraint.h.
int btGeneric6DofConstraint::setLinearLimits | ( | btConstraintInfo2 * | info, |
int | row, | ||
const btTransform & | transA, | ||
const btTransform & | transB, | ||
const btVector3 & | linVelA, | ||
const btVector3 & | linVelB, | ||
const btVector3 & | angVelA, | ||
const btVector3 & | angVelB | ||
) | [protected] |
void btGeneric6DofConstraint::setLinearLowerLimit | ( | const btVector3 & | linearLower | ) | [inline] |
Definition at line 445 of file btGeneric6DofConstraint.h.
void btGeneric6DofConstraint::setLinearUpperLimit | ( | const btVector3 & | linearUpper | ) | [inline] |
Definition at line 455 of file btGeneric6DofConstraint.h.
virtual void btGeneric6DofConstraint::setParam | ( | int | num, |
btScalar | value, | ||
int | axis = -1 |
||
) | [virtual] |
override the default global value of a parameter (such as ERP or CFM), optionally provide the axis (0..5). If no axis is provided, it uses the default axis for this constraint.
Implements btTypedConstraint.
void btGeneric6DofConstraint::setUseFrameOffset | ( | bool | frameOffsetOnOff | ) | [inline] |
Definition at line 543 of file btGeneric6DofConstraint.h.
bool btGeneric6DofConstraint::testAngularLimitMotor | ( | int | axis_index | ) |
Test angular limit.
Calculates angular correction and returns true if limit needs to be corrected.
void btGeneric6DofConstraint::updateRHS | ( | btScalar | timeStep | ) |
btVector3 btGeneric6DofConstraint::m_AnchorPos [protected] |
Definition at line 312 of file btGeneric6DofConstraint.h.
btRotationalLimitMotor btGeneric6DofConstraint::m_angularLimits[3] [protected] |
hinge_parameters
Definition at line 295 of file btGeneric6DofConstraint.h.
btVector3 btGeneric6DofConstraint::m_calculatedAxis[3] [protected] |
Definition at line 306 of file btGeneric6DofConstraint.h.
btVector3 btGeneric6DofConstraint::m_calculatedAxisAngleDiff [protected] |
Definition at line 305 of file btGeneric6DofConstraint.h.
btVector3 btGeneric6DofConstraint::m_calculatedLinearDiff [protected] |
Definition at line 307 of file btGeneric6DofConstraint.h.
Definition at line 303 of file btGeneric6DofConstraint.h.
Definition at line 304 of file btGeneric6DofConstraint.h.
btScalar btGeneric6DofConstraint::m_factA [protected] |
Definition at line 308 of file btGeneric6DofConstraint.h.
btScalar btGeneric6DofConstraint::m_factB [protected] |
Definition at line 309 of file btGeneric6DofConstraint.h.
int btGeneric6DofConstraint::m_flags [protected] |
Definition at line 317 of file btGeneric6DofConstraint.h.
btTransform btGeneric6DofConstraint::m_frameInA [protected] |
the constraint space w.r.t body A
relative_frames
Definition at line 277 of file btGeneric6DofConstraint.h.
btTransform btGeneric6DofConstraint::m_frameInB [protected] |
the constraint space w.r.t body B
Definition at line 278 of file btGeneric6DofConstraint.h.
bool btGeneric6DofConstraint::m_hasStaticBody [protected] |
Definition at line 310 of file btGeneric6DofConstraint.h.
btJacobianEntry btGeneric6DofConstraint::m_jacAng[3] [protected] |
3 orthogonal angular constraints
Definition at line 284 of file btGeneric6DofConstraint.h.
btJacobianEntry btGeneric6DofConstraint::m_jacLinear[3] [protected] |
Linear_Limit_parameters
Definition at line 289 of file btGeneric6DofConstraint.h.
btScalar btGeneric6DofConstraint::m_timeStep [protected] |
temporal variables
Definition at line 302 of file btGeneric6DofConstraint.h.
bool btGeneric6DofConstraint::m_useLinearReferenceFrameA [protected] |
Definition at line 314 of file btGeneric6DofConstraint.h.
bool btGeneric6DofConstraint::m_useOffsetForConstraintFrame [protected] |
Definition at line 315 of file btGeneric6DofConstraint.h.
for backwards compatibility during the transition to 'getInfo/getInfo2'
Definition at line 350 of file btGeneric6DofConstraint.h.