PxArticulationCache
Defined in include/PxArticulationReducedCoordinate.h
-
class PxArticulationCache
Data structure used to read and write internal articulation data.
See also
PxArticulationCacheFlag, PxArticulationReducedCoordinate::createCache, PxArticulationReducedCoordinate::applyCache, PxArticulationReducedCoordinate::copyInternalStateToCache
Public Functions
-
inline PxArticulationCache()
-
void release()
Releases an articulation cache.
See also
PxArticulationReducedCoordinate::createCache, PxArticulationReducedCoordinate::applyCache, PxArticulationReducedCoordinate::copyInternalStateToCache
Public Members
-
PxSpatialForce *externalForces
External forces acting on the articulation links for inverse dynamics computation.
N = getNbLinks().
Indexing follows the low-level link indices, see PxArticulationLink::getLinkIndex.
The forces are with respect to the center of mass of the link.
This field cannot be used to apply forces to links during the next PxScene::simulate() call. Use PxRigidBody::addForce and related functions instead.
See also
PxArticulationReducedCoordinate::computeGeneralizedExternalForce
-
PxReal *denseJacobian
Dense Jacobian data.
N = nbRows * nbCols = (6 * getNbLinks()) * (6 + getDofs()) -> size includes possible floating-base DOFs regardless of PxArticulationFlag::eFIX_BASE flag.
The links, i.e. rows are in order of the low-level link indices (minus one if PxArticulationFlag::eFIX_BASE is true), see PxArticulationLink::getLinkIndex. The corresponding spatial velocities are stacked [vx; vy; vz; wx; wy; wz], where vx and wx refer to the linear and rotational velocity in world X.
The DOFs, i.e. column indices correspond to the low-level DOF indices, see PxArticulationCache::jointVelocity.
See also
PxArticulationReducedCoordinate::computeDenseJacobian
-
PxReal *massMatrix
The generalized mass matrix that maps joint accelerations to joint forces.
N = getDofs() * getDofs().
The indexing follows the internal DOF index order, see PxArticulationCache::jointVelocity.
See also
PxArticulationReducedCoordinate::computeGeneralizedMassMatrix
-
PxReal *jointVelocity
The articulation joint DOF velocities.
N = getDofs().
Read/write using PxArticulationCacheFlag::eVELOCITY.
The indexing follows the internal DOF index order. Therefore, the application should calculate the DOF data indices by summing the joint DOFs in the order of the links’ low-level indices (see the manual Section “Cache Indexing” for a snippet for this calculation):
Low-level link index: | link 0 | link 1 | link 2 | link 3 | ... | <- PxArticulationLink::getLinkIndex()
Link inbound joint DOF: | 0 | 1 | 2 | 1 | ... | <- PxArticulationLink::getInboundJointDof()
The root link always has low-level index 0 and always has zero inbound joint DOFs. The link DOF indexing follows the order in PxArticulationAxis::Enum. For example, assume that low-level link 2 has an inbound spherical joint with two DOFs: eSWING1 and eSWING2. The corresponding low-level joint DOF indices are therefore 1 for eSWING1 and 2 for eSWING2.Low-level DOF index: | - | 0 | 1, 2 | 3 | ... |
-
PxReal *jointAcceleration
The articulation joint DOF accelerations.
N = getDofs().
Read using PxArticulationCacheFlag::eACCELERATION.
The indexing follows the internal DOF index order, see PxArticulationCache::jointVelocity.
Delta joint DOF velocities can be computed from acceleration * dt.
-
PxReal *jointPosition
The articulation joint DOF positions.
N = getDofs().
Read/write using PxArticulationCacheFlag::ePOSITION.
The indexing follows the internal DOF index order, see PxArticulationCache::jointVelocity.
For spherical joints, the joint position for each axis on the joint must be in range [-Pi, Pi].
-
PxReal *jointForce
The articulation joint DOF forces.
N = getDofs().
Read/Write using PxArticulationCacheFlag::eFORCE.
The indexing follows the internal DOF index order, see PxArticulationCache::jointVelocity.
Applied joint forces persist and are applied each frame until changed.
-
PxReal *jointTargetPositions
The articulation joint drive target positions.
N = getDofs().
Write using PxArticulationCacheFlag::eJOINT_TARGET_POSITIONS.
The indexing follows the internal DOF index order, see PxArticulationCache::jointVelocity.
-
PxReal *jointTargetVelocities
The articulation joint drive target velocities.
N = getDofs().
Write using PxArticulationCacheFlag::eJOINT_TARGET_VELOCITIES.
The indexing follows the internal DOF index order, see PxArticulationCache::jointVelocity.
-
PxSpatialVelocity *linkVelocity
Link spatial velocity.
N = getNbLinks().
Read using PxArticulationCacheFlag::eLINK_VELOCITY.
The indexing follows the internal link indexing, see PxArticulationLink::getLinkIndex.
The velocity is with respect to the link’s center of mass but represented in world space.
See also
PxRigidBody::getCMassLocalPose
-
PxSpatialVelocity *linkAcceleration
Link classical acceleration.
N = getNbLinks().
Read using PxArticulationCacheFlag::eLINK_ACCELERATION.
The indexing follows the internal link indexing, see PxArticulationLink::getLinkIndex.
The acceleration is with respect to the link’s center of mass.
See also
PxArticulationReducedCoordinate::getLinkAcceleration, PxRigidBody::getCMassLocalPose
-
PxSpatialForce *linkIncomingJointForce
Link incoming joint force, i.e.
the total force transmitted from the parent link to this link.
N = getNbLinks().
Read using PxArticulationCacheFlag::eLINK_INCOMING_JOINT_FORCE.
The indexing follows the internal link indexing, see PxArticulationLink::getLinkIndex.
The force is reported in the child joint frame of the link’s incoming joint.
See also
PxArticulationJointReducedCoordinate::getChildPose
Note
The root link reports a zero spatial force.
-
PxVec3 *linkForce
Link force, i.e.
an external force applied to the link’s center of mass.
N = getNbLinks().
Write using PxArticulationCacheFlag::eLINK_FORCE.
The indexing follows the internal link indexing, see PxArticulationLink::getLinkIndex.
The force is given in world space.
-
PxVec3 *linkTorque
Link torque, i.e.
an external torque applied to the link.
N = getNbLinks().
Write using PxArticulationCacheFlag::eLINK_TORQUE.
The indexing follows the internal link indexing, see PxArticulationLink::getLinkIndex.
The torque is given in world space.
-
PxArticulationRootLinkData *rootLinkData
Root link transform, velocities, and accelerations.
N = 1.
Read/write using PxArticulationCacheFlag::eROOT_TRANSFORM and PxArticulationCacheFlag::eROOT_VELOCITIES (accelerations are read-only).
See also
PxArticulationRootLinkData
-
PxReal *coefficientMatrix
Constraint coefficient matrix.
- Deprecated:
The API related to loop joints will be removed in a future version once a replacement is made available.
N = getCoefficentMatrixSize().
The user needs to allocate memory and set this member to the allocated memory.
See also
PxArticulationReducedCoordinate::computeCoefficientMatrix
-
PxReal *lambda
Constraint lambda values (impulses applied by the respective constraints).
- Deprecated:
The API related to loop joints will be removed in a future version once a replacement is made available.
N = getNbLoopJoints().
The user needs to allocate memory and set this member to the allocated memory.
See also
PxArticulationReducedCoordinate::computeLambda
-
void *scratchMemory
The scratch memory is used for internal calculations.
-
void *scratchAllocator
The scratch allocator is used for internal calculations.
-
inline PxArticulationCache()