PxArticulationReducedCoordinate

Defined in include/PxArticulationReducedCoordinate.h

Inheritance Relationships

Base Type

class PxArticulationReducedCoordinate : public PxBase

A tree structure of bodies connected by joints that is treated as a unit by the dynamics solver.

Parametrized in reduced (joint) coordinates.

Public Functions

virtual PxScene *getScene() const = 0

Returns the scene which this articulation belongs to.

See also

PxScene

Returns

Owner Scene. NULL if not part of a scene.

virtual void setSolverIterationCounts(PxU32 minPositionIters, PxU32 minVelocityIters = 1) = 0

Sets the solver iteration counts for the articulation.

The solver iteration count determines how accurately contacts, drives, and limits are resolved. Setting a higher position iteration count may therefore help in scenarios where the articulation is subject to many constraints; for example, a manipulator articulation with drives and joint limits that is grasping objects, or several such articulations interacting through contacts. Other situations where higher position iterations may improve simulation fidelity are: large mass ratios within the articulation or between the articulation and an object in contact with it; or strong drives in the articulation being used to manipulate a light object.

If intersecting bodies are being depenetrated too violently, increase the number of velocity iterations. More velocity iterations will drive the relative exit velocity of the intersecting objects closer to the correct value given the restitution.

Note

This call may not be made during simulation.

Parameters
  • minPositionIters[in] Number of position iterations the solver should perform for this articulation. Range: [1,255]

  • minVelocityIters[in] Number of velocity iterations the solver should perform for this articulation. Range: [1,255]

virtual void getSolverIterationCounts(PxU32 &minPositionIters, PxU32 &minVelocityIters) const = 0

Returns the solver iteration counts.

virtual bool isSleeping() const = 0

Returns true if this articulation is sleeping.

When an actor does not move for a period of time, it is no longer simulated in order to save time. This state is called sleeping. However, because the object automatically wakes up when it is either touched by an awake object, or a sleep-affecting property is changed by the user, the entire sleep mechanism should be transparent to the user.

An articulation can only go to sleep if all links are ready for sleeping. An articulation is guaranteed to be awake if at least one of the following holds:

  • The wake counter is positive (see setWakeCounter()).

  • The linear or angular velocity of any link is non-zero.

  • A non-zero force or torque has been applied to the articulation or any of its links.

If an articulation is sleeping, the following state is guaranteed:

  • The wake counter is zero.

  • The linear and angular velocity of all links is zero.

  • There is no force update pending.

When an articulation gets inserted into a scene, it will be considered asleep if all the points above hold, else it will be treated as awake.

If an articulation is asleep after the call to PxScene::fetchResults() returns, it is guaranteed that the poses of the links were not changed. You can use this information to avoid updating the transforms of associated objects.

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation, except in a split simulation in-between PxScene::fetchCollision and PxScene::advance.

Returns

True if the articulation is sleeping.

virtual void setSleepThreshold(PxReal threshold) = 0

Sets the mass-normalized energy threshold below which the articulation may go to sleep.

The articulation will sleep if the energy of each link is below this threshold.

Note

This call may not be made during simulation.

Parameters

threshold[in] Energy below which the articulation may go to sleep. Range: [0, PX_MAX_F32)

virtual PxReal getSleepThreshold() const = 0

Returns the mass-normalized energy below which the articulation may go to sleep.

Returns

The energy threshold for sleeping.

virtual void setStabilizationThreshold(PxReal threshold) = 0

Sets the mass-normalized kinetic energy threshold below which the articulation may participate in stabilization.

Articulations whose kinetic energy divided by their mass is above this threshold will not participate in stabilization.

This value has no effect if PxSceneFlag::eENABLE_STABILIZATION was not enabled on the PxSceneDesc.

Default: 0.01 * PxTolerancesScale::speed * PxTolerancesScale::speed

Note

This call may not be made during simulation.

Parameters

threshold[in] Energy below which the articulation may participate in stabilization. Range: [0,inf)

virtual PxReal getStabilizationThreshold() const = 0

Returns the mass-normalized kinetic energy below which the articulation may participate in stabilization.

Articulations whose kinetic energy divided by their mass is above this threshold will not participate in stabilization.

Returns

The energy threshold for participating in stabilization.

virtual void setWakeCounter(PxReal wakeCounterValue) = 0

Sets the wake counter for the articulation in seconds.

  • The wake counter value determines the minimum amount of time until the articulation can be put to sleep.

  • An articulation will not be put to sleep if the energy is above the specified threshold (see setSleepThreshold()) or if other awake objects are touching it.

  • Passing in a positive value will wake up the articulation automatically.

Default: 0.4s (which corresponds to 20 frames for a time step of 0.02s)

Note

This call may not be made during simulation, except in a split simulation in-between PxScene::fetchCollision and PxScene::advance.

Parameters

wakeCounterValue[in] Wake counter value in seconds. Range: [0, PX_MAX_F32)

virtual PxReal getWakeCounter() const = 0

Returns the wake counter of the articulation in seconds.

Note

This call may not be made during simulation, except in a split simulation in-between PxScene::fetchCollision and PxScene::advance.

Returns

The wake counter of the articulation in seconds.

virtual void wakeUp() = 0

Wakes up the articulation if it is sleeping.

  • The articulation will get woken up and might cause other touching objects to wake up as well during the next simulation step.

  • This will set the wake counter of the articulation to the value specified in PxSceneDesc::wakeCounterResetValue.

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation, except in a split simulation in-between PxScene::fetchCollision and PxScene::advance.

virtual void putToSleep() = 0

Forces the articulation to sleep.

  • The articulation will stay asleep during the next simulation step if not touched by another non-sleeping actor.

  • This will set any applied force, the velocity, and the wake counter of all bodies in the articulation to zero.

Note

This call may not be made during simulation, and may only be made on articulations that are in a scene.

virtual void setMaxCOMLinearVelocity(const PxReal maxLinearVelocity) = 0

Sets the limit on the magnitude of the linear velocity of the articulation’s center of mass.

  • The limit acts on the linear velocity of the entire articulation. The velocity is calculated from the total momentum and the spatial inertia of the articulation.

  • The limit only applies to floating-base articulations.

  • A benefit of the COM velocity limit is that it is evenly applied to the whole articulation, which results in fewer visual artifacts compared to link rigid-body damping or joint-velocity limits. However, these per-link or per-degree-of-freedom limits may still help avoid numerical issues.

Note

This call may not be made during simulation.

Parameters

maxLinearVelocity[in] The maximal linear velocity magnitude. Range: [0, PX_MAX_F32); Default: PX_MAX_F32.

virtual PxReal getMaxCOMLinearVelocity() const = 0

Gets the limit on the magnitude of the linear velocity of the articulation’s center of mass.

Returns

The maximal linear velocity magnitude.

virtual void setMaxCOMAngularVelocity(const PxReal maxAngularVelocity) = 0

Sets the limit on the magnitude of the angular velocity at the articulation’s center of mass.

  • The limit acts on the angular velocity of the entire articulation. The velocity is calculated from the total momentum and the spatial inertia of the articulation.

  • The limit only applies to floating-base articulations.

  • A benefit of the COM velocity limit is that it is evenly applied to the whole articulation, which results in fewer visual artifacts compared to link rigid-body damping or joint-velocity limits. However, these per-link or per-degree-of-freedom limits may still help avoid numerical issues.

Note

This call may not be made during simulation.

Parameters

maxAngularVelocity[in] The maximal angular velocity magnitude. Range: [0, PX_MAX_F32); Default: PX_MAX_F32.

virtual PxReal getMaxCOMAngularVelocity() const = 0

Gets the limit on the magnitude of the angular velocity at the articulation’s center of mass.

Returns

The maximal angular velocity magnitude.

virtual PxArticulationLink *createLink(PxArticulationLink *parent, const PxTransform &pose) = 0

Adds a link to the articulation with default attribute values.

Note

Creating a link is not allowed while the articulation is in a scene. In order to add a link, remove and then re-add the articulation to the scene.

Parameters
  • parent[in] The parent link in the articulation. Must be NULL if (and only if) this is the root link.

  • pose[in] The initial pose of the new link. Must be a valid transform.

Returns

The new link, or NULL if the link cannot be created.

virtual void release() = 0

Releases the articulation, and all its links and corresponding joints.

Attached sensors and tendons are released automatically when the articulation is released.

Note

This call may not be made during simulation.

virtual PxU32 getNbLinks() const = 0

Returns the number of links in the articulation.

Returns

The number of links.

virtual PxU32 getLinks(PxArticulationLink **userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0

Returns the set of links in the articulation in the order that they were added to the articulation using createLink.

Parameters
  • userBuffer[in] Buffer into which to write the array of articulation link pointers.

  • bufferSize[in] The size of the buffer. If the buffer is not large enough to contain all the pointers to links, only as many as will fit are written.

  • startIndex[in] Index of first link pointer to be retrieved.

Returns

The number of links written into the buffer.

virtual PxU32 getNbShapes() const = 0

Returns the number of shapes in the articulation.

Returns

The number of shapes.

virtual void setName(const char *name) = 0

Sets a name string for the articulation that can be retrieved with getName().

This is for debugging and is not used by the SDK. The string is not copied by the SDK, only the pointer is stored.

See also

getName()

Parameters

name[in] String to set the articulation’s name to.

virtual const char *getName() const = 0

Returns the name string set with setName().

See also

setName()

Returns

Name string associated with the articulation.

virtual PxBounds3 getWorldBounds(float inflation = 1.01f) const = 0

Returns the axis-aligned bounding box enclosing the articulation.

See also

PxBounds3

Note

It is not allowed to use this method while the simulation is running, except in a split simulation during PxScene::collide() and up to PxScene::advance(), and in PxContactModifyCallback or in contact report callbacks.

Parameters

inflation[in] Scale factor for computed world bounds. Box extents are multiplied by this value.

Returns

The articulation’s bounding box.

virtual PxAggregate *getAggregate() const = 0

Returns the aggregate the articulation might be a part of.

See also

PxAggregate

Returns

The aggregate the articulation is a part of, or NULL if the articulation does not belong to an aggregate.

virtual void setArticulationFlags(PxArticulationFlags flags) = 0

Sets flags on the articulation.

Note

This call may not be made during simulation.

Parameters

flags[in] The articulation flags.

virtual void setArticulationFlag(PxArticulationFlag::Enum flag, bool value) = 0

Raises or clears a flag on the articulation.

Note

This call may not be made during simulation.

Parameters
  • flag[in] The articulation flag.

  • value[in] The value to set the flag to.

virtual PxArticulationFlags getArticulationFlags() const = 0

Returns the articulation’s flags.

Returns

The flags.

virtual PxU32 getDofs() const = 0

Returns the total number of joint degrees-of-freedom (DOFs) of the articulation.

  • The six DOFs of the base of a floating-base articulation are not included in this count.

  • Example: Both a fixed-base and a floating-base double-pendulum with two revolute joints will have getDofs() == 2.

  • The return value is only valid for articulations that are in a scene.

Returns

The number of joint DOFs, or 0xFFFFFFFF if the articulation is not in a scene.

virtual PxArticulationCache *createCache() const = 0

Creates an articulation cache that can be used to read and write internal articulation data.

  • When the structure of the articulation changes (e.g. adding a link or sensor) after the cache was created, the cache needs to be released and recreated.

  • Free the memory allocated for the cache by calling the release() method on the cache.

  • Caches can only be created by articulations that are in a scene.

Returns

The cache, or NULL if the articulation is not in a scene.

virtual PxU32 getCacheDataSize() const = 0

Returns the size of the articulation cache in bytes.

  • The size does not include: the user-allocated memory for the coefficient matrix or lambda values; the scratch-related memory/members; and the cache version. See comment in PxArticulationCache.

  • The return value is only valid for articulations that are in a scene.

Returns

The byte size of the cache, or 0xFFFFFFFF if the articulation is not in a scene.

virtual void zeroCache(PxArticulationCache &cache) const = 0

Zeroes all data in the articulation cache, except user-provided and scratch memory, and cache version.

Note

This call may only be made on articulations that are in a scene.

virtual void applyCache(PxArticulationCache &cache, const PxArticulationCacheFlags flags, bool autowake = true) = 0

Applies the data in the cache to the articulation.

This call wakes the articulation if it is sleeping, and the autowake parameter is true (default) or:

  • a nonzero joint velocity is applied or

  • a nonzero joint force is applied or

  • a nonzero root velocity is applied

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation.

Parameters
  • cache[in] The articulation data.

  • flags[in] Indicate which data in the cache to apply to the articulation.

  • autowake[in] If true, the call wakes up the articulation and increases the wake counter to PxSceneDesc::wakeCounterResetValue if the counter value is below the reset value.

virtual void copyInternalStateToCache(PxArticulationCache &cache, const PxArticulationCacheFlags flags) const = 0

Copies internal data of the articulation to the cache.

See also

PxArticulationCache, PxArticulationCacheFlags, createCache, applyCache

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation.

Parameters
  • cache[in] The articulation data.

  • flags[in] Indicate which data to copy from the articulation to the cache.

virtual void packJointData(const PxReal *maximum, PxReal *reduced) const = 0

Converts maximal-coordinate joint DOF data to reduced coordinates.

  • Indexing into the maximal joint DOF data is via the link’s low-level index minus 1 (the root link is not included).

  • The reduced-coordinate data follows the cache indexing convention, see PxArticulationCache::jointVelocity.

See also

unpackJointData

Note

The articulation must be in a scene.

Parameters
  • maximum[in] The maximal-coordinate joint DOF data, N = (getNbLinks() - 1) * 6

  • reduced[out] The reduced-coordinate joint DOF data, N = getDofs()

virtual void unpackJointData(const PxReal *reduced, PxReal *maximum) const = 0

Converts reduced-coordinate joint DOF data to maximal coordinates.

  • Indexing into the maximal joint DOF data is via the link’s low-level index minus 1 (the root link is not included).

  • The reduced-coordinate data follows the cache indexing convention, see PxArticulationCache::jointVelocity.

See also

packJointData

Note

The articulation must be in a scene.

Parameters
  • reduced[in] The reduced-coordinate joint DOF data, N = getDofs().

  • maximum[out] The maximal-coordinate joint DOF data, N = (getNbLinks() - 1) * 6.

virtual void commonInit() const = 0

Prepares common articulation data based on articulation pose for inverse dynamics calculations.

Usage:

  1. Set articulation pose (joint positions and base transform) via articulation cache and applyCache().

  2. Call commonInit.

  3. Call inverse dynamics computation method.

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation.

virtual void computeGeneralizedGravityForce(PxArticulationCache &cache) const = 0

Computes the joint DOF forces required to counteract gravitational forces for the given articulation pose.

  • Inputs: Articulation pose (joint positions + base transform).

  • Outputs: Joint forces to counteract gravity (in cache).

  • The joint forces returned are determined purely by gravity for the articulation in the current joint and base pose, and joints at rest; i.e. external forces, joint velocities, and joint accelerations are set to zero. Joint drives are also not considered in the computation.

  • commonInit() must be called before the computation, and after setting the articulation pose via applyCache().

See also

commonInit

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation.

Parameters

cache[out] Out: PxArticulationCache::jointForce.

virtual void computeCoriolisAndCentrifugalForce(PxArticulationCache &cache) const = 0

Computes the joint DOF forces required to counteract Coriolis and centrifugal forces for the given articulation state.

  • Inputs: Articulation state (joint positions and velocities (in cache), and base transform and spatial velocity).

  • Outputs: Joint forces to counteract Coriolis and centrifugal forces (in cache).

  • The joint forces returned are determined purely by the articulation’s state; i.e. external forces, gravity, and joint accelerations are set to zero. Joint drives and potential damping terms, such as link angular or linear damping, or joint friction, are also not considered in the computation.

  • Prior to the computation, update/set the base spatial velocity with PxArticulationCache::rootLinkData and applyCache().

  • commonInit() must be called before the computation, and after setting the articulation pose via applyCache().

See also

commonInit

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation.

Parameters

cache[inout] In: PxArticulationCache::jointVelocity; Out: PxArticulationCache::jointForce.

virtual void computeGeneralizedExternalForce(PxArticulationCache &cache) const = 0

Computes the joint DOF forces required to counteract external spatial forces applied to articulation links.

  • Inputs: External forces on links (in cache), articulation pose (joint positions + base transform).

  • Outputs: Joint forces to counteract the external forces (in cache).

  • Only the external spatial forces provided in the cache and the articulation pose are considered in the computation.

  • The external spatial forces are with respect to the links’ centers of mass, and not the actor’s origin.

  • commonInit() must be called before the computation, and after setting the articulation pose via applyCache().

See also

commonInit

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation.

Parameters

cache[inout] In: PxArticulationCache::externalForces; Out: PxArticulationCache::jointForce.

virtual void computeJointAcceleration(PxArticulationCache &cache) const = 0

Computes the joint accelerations for the given articulation state and joint forces.

  • Inputs: Joint forces (in cache) and articulation state (joint positions and velocities (in cache), and base transform and spatial velocity).

  • Outputs: Joint accelerations (in cache).

  • The computation includes Coriolis terms and gravity. However, joint drives and potential damping terms are not considered in the computation (for example, linear link damping or joint friction).

  • Prior to the computation, update/set the base spatial velocity with PxArticulationCache::rootLinkData and applyCache().

  • commonInit() must be called before the computation, and after setting the articulation pose via applyCache().

See also

commonInit

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation.

Parameters

cache[inout] In: PxArticulationCache::jointForce and PxArticulationCache::jointVelocity; Out: PxArticulationCache::jointAcceleration.

virtual void computeJointForce(PxArticulationCache &cache) const = 0

Computes the joint forces for the given articulation state and joint accelerations, not considering gravity.

  • Inputs: Joint accelerations (in cache) and articulation state (joint positions and velocities (in cache), and base transform and spatial velocity).

  • Outputs: Joint forces (in cache).

  • The computation includes Coriolis terms. However, joint drives and potential damping terms are not considered in the computation (for example, linear link damping or joint friction).

  • Prior to the computation, update/set the base spatial velocity with PxArticulationCache::rootLinkData and applyCache().

  • commonInit() must be called before the computation, and after setting the articulation pose via applyCache().

See also

commonInit

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation.

Parameters

cache[inout] In: PxArticulationCache::jointAcceleration and PxArticulationCache::jointVelocity; Out: PxArticulationCache::jointForce.

virtual void computeDenseJacobian(PxArticulationCache &cache, PxU32 &nRows, PxU32 &nCols) const = 0

Compute the dense Jacobian for the articulation in world space, including the DOFs of a potentially floating base.

This computes the dense representation of an inherently sparse matrix. Multiplication with this matrix maps joint space velocities to world-space linear and angular (i.e. spatial) velocities of the centers of mass of the links.

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation.

Parameters
  • cache[out] Sets cache.denseJacobian matrix. The matrix is indexed [nCols * row + column].

  • nRows[out] Set to number of rows in matrix, which corresponds to nbLinks() * 6, minus 6 if PxArticulationFlag::eFIX_BASE is true.

  • nCols[out] Set to number of columns in matrix, which corresponds to the number of joint DOFs, plus 6 in the case PxArticulationFlag::eFIX_BASE is false.

virtual void computeCoefficientMatrix(PxArticulationCache &cache) const = 0

Computes the coefficient matrix for contact forces.

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation.

Parameters

cache[out] Out: PxArticulationCache::coefficientMatrix.

virtual bool computeLambda(PxArticulationCache &cache, PxArticulationCache &initialState, const PxReal *const jointTorque, const PxU32 maxIter) const = 0

Computes the lambda values when the test impulse is 1.

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation.

Parameters
  • cache[out] Out: PxArticulationCache::lambda.

  • initialState[in] The initial state of the articulation system.

  • jointTorque[in] M(q)*qddot + C(q,qdot) + g(q) <- calculate by summing joint forces obtained with computeJointForce and computeGeneralizedGravityForce.

  • maxIter[in] Maximum number of solver iterations to run. If the system converges, fewer iterations may be used.

Returns

True if convergence was achieved within maxIter; False if convergence was not achieved or the operation failed otherwise.

virtual void computeGeneralizedMassMatrix(PxArticulationCache &cache) const = 0

Compute the joint-space inertia matrix that maps joint accelerations to joint forces: forces = M * accelerations.

  • Inputs: Articulation pose (joint positions and base transform).

  • Outputs: Mass matrix (in cache).

commonInit() must be called before the computation, and after setting the articulation pose via applyCache().

See also

commonInit

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation.

Parameters

cache[out] Out: PxArticulationCache::massMatrix.

virtual void addLoopJoint(PxConstraint *joint) = 0

Adds a loop joint to the articulation system for inverse dynamics.

Note

This call may not be made during simulation.

Parameters

joint[in] The joint to add.

virtual void removeLoopJoint(PxConstraint *joint) = 0

Removes a loop joint from the articulation for inverse dynamics.

Note

This call may not be made during simulation.

Parameters

joint[in] The joint to remove.

virtual PxU32 getNbLoopJoints() const = 0

Returns the number of loop joints in the articulation for inverse dynamics.

Returns

The number of loop joints.

virtual PxU32 getLoopJoints(PxConstraint **userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0

Returns the set of loop constraints (i.e.

joints) in the articulation.

Parameters
  • userBuffer[in] Target buffer for the constraint pointers.

  • bufferSize[in] The size of the buffer. If this is not large enough to contain all the pointers to the constraints, only as many as will fit are written. Use getNbLoopJoints() to size the buffer for retrieving all constraints.

  • startIndex[in] Index of first constraint pointer to be retrieved.

Returns

The number of constraints written into the buffer.

virtual PxU32 getCoefficientMatrixSize() const = 0

Returns the required size of the coefficient matrix in the articulation.

Note

This call may only be made on articulations that are in a scene.

Returns

Size of the coefficient matrix (equal to getDofs() * getNbLoopJoints()).

virtual void setRootGlobalPose(const PxTransform &pose, bool autowake = true) = 0

Sets the root link transform (world to actor frame).

  • For performance, prefer PxArticulationCache::rootLinkData to set the root link transform in a batch articulation state update.

  • Use updateKinematic() after all state updates to the articulation via non-cache API such as this method, in order to update link states for the next simulation frame or querying.

Note

This call may not be made during simulation.

Parameters
  • pose[in] The new root link transform.

  • autowake[in] If true and the articulation is in a scene, the call wakes up the articulation and increases the wake counter to PxSceneDesc::wakeCounterResetValue if the counter value is below the reset value.

virtual PxTransform getRootGlobalPose() const = 0

Returns the root link transform (world to actor frame).

For performance, prefer PxArticulationCache::rootLinkData to get the root link transform in a batch query.

Note

This call is not allowed while the simulation is running except in a split simulation during PxScene::collide() and up to PxScene::advance(), and in PxContactModifyCallback or in contact report callbacks.

Returns

The root link transform.

virtual void setRootLinearVelocity(const PxVec3 &linearVelocity, bool autowake = true) = 0

Sets the root link linear center-of-mass velocity.

  • The linear velocity is with respect to the link’s center of mass and not the actor frame origin.

  • For performance, prefer PxArticulationCache::rootLinkData to set the root link velocity in a batch articulation state update.

  • The articulation is woken up if the input velocity is nonzero (ignoring autowake) and the articulation is in a scene.

  • Use updateKinematic() after all state updates to the articulation via non-cache API such as this method, in order to update link states for the next simulation frame or querying.

Note

This call may not be made during simulation, except in a split simulation in-between PxScene::fetchCollision and PxScene::advance.

Parameters
  • linearVelocity[in] The new root link center-of-mass linear velocity.

  • autowake[in] If true and the articulation is in a scene, the call wakes up the articulation and increases the wake counter to PxSceneDesc::wakeCounterResetValue if the counter value is below the reset value.

virtual PxVec3 getRootLinearVelocity(void) const = 0

Gets the root link center-of-mass linear velocity.

  • The linear velocity is with respect to the link’s center of mass and not the actor frame origin.

  • For performance, prefer PxArticulationCache::rootLinkData to get the root link velocity in a batch query.

Note

This call is not allowed while the simulation is running except in a split simulation during PxScene::collide() and up to PxScene::advance(), and in PxContactModifyCallback or in contact report callbacks.

Returns

The root link center-of-mass linear velocity.

virtual void setRootAngularVelocity(const PxVec3 &angularVelocity, bool autowake = true) = 0

Sets the root link angular velocity.

  • For performance, prefer PxArticulationCache::rootLinkData to set the root link velocity in a batch articulation state update.

  • The articulation is woken up if the input velocity is nonzero (ignoring autowake) and the articulation is in a scene.

  • Use updateKinematic() after all state updates to the articulation via non-cache API such as this method, in order to update link states for the next simulation frame or querying.

Note

This call may not be made during simulation, except in a split simulation in-between PxScene::fetchCollision and PxScene::advance.

Parameters
  • angularVelocity[in] The new root link angular velocity.

  • autowake[in] If true and the articulation is in a scene, the call wakes up the articulation and increases the wake counter to PxSceneDesc::wakeCounterResetValue if the counter value is below the reset value.

virtual PxVec3 getRootAngularVelocity(void) const = 0

Gets the root link angular velocity.

For performance, prefer PxArticulationCache::rootLinkData to get the root link velocity in a batch query.

Note

This call is not allowed while the simulation is running except in a split simulation during PxScene::collide() and up to PxScene::advance(), and in PxContactModifyCallback or in contact report callbacks.

Returns

The root link angular velocity.

virtual PxSpatialVelocity getLinkAcceleration(const PxU32 linkId) = 0

Returns the (classical) link acceleration in world space for the given low-level link index.

  • The returned acceleration is not a spatial, but a classical, i.e. body-fixed acceleration (https://en.wikipedia.org/wiki/Spatial_acceleration).

  • The (linear) acceleration is with respect to the link’s center of mass and not the actor frame origin.

Note

This call may only be made on articulations that are in a scene, and it is not allowed to use this method while the simulation is running except in a split simulation during PxScene::collide() and up to PxScene::advance(), and in PxContactModifyCallback or in contact report callbacks.

Parameters

linkId[in] The low-level link index, see PxArticulationLink::getLinkIndex.

Returns

The link’s center-of-mass classical acceleration, or 0 if the call is made before the articulation participated in a first simulation step.

virtual PxU32 getGpuArticulationIndex() = 0

Returns the GPU articulation index.

Returns

The GPU index, or 0xFFFFFFFF if the articulation is not in a scene or PxSceneFlag::eSUPPRESS_READBACK is not set.

virtual PxArticulationSpatialTendon *createSpatialTendon() = 0

Creates a spatial tendon to attach to the articulation with default attribute values.

Note

Creating a spatial tendon is not allowed while the articulation is in a scene. In order to add the tendon, remove and then re-add the articulation to the scene.

Returns

The new spatial tendon.

virtual PxArticulationFixedTendon *createFixedTendon() = 0

Creates a fixed tendon to attach to the articulation with default attribute values.

Note

Creating a fixed tendon is not allowed while the articulation is in a scene. In order to add the tendon, remove and then re-add the articulation to the scene.

Returns

The new fixed tendon.

virtual PxArticulationSensor *createSensor(PxArticulationLink *link, const PxTransform &relativePose) = 0

Creates a force sensor attached to a link of the articulation.

Note

Creating a sensor is not allowed while the articulation is in a scene. In order to add the sensor, remove and then re-add the articulation to the scene.

Parameters
  • link[in] The link to attach the sensor to.

  • relativePose[in] The sensor frame’s relative pose to the link’s body frame, i.e. the transform body frame -> sensor frame. The link body frame is at the center of mass and aligned with the principal axes of inertia, see PxRigidBody::getCMassLocalPose.

Returns

The new sensor.

virtual PxU32 getSpatialTendons(PxArticulationSpatialTendon **userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0

Returns the spatial tendons attached to the articulation.

The order of the tendons in the buffer is not necessarily identical to the order in which the tendons were added to the articulation.

Parameters
  • userBuffer[in] The buffer into which to write the array of pointers to the tendons.

  • bufferSize[in] The size of the buffer. If this is not large enough to contain all the pointers to tendons, only as many as will fit are written. Use getNbSpatialTendons to size for all attached tendons.

  • startIndex[in] Index of first tendon pointer to be retrieved.

Returns

The number of tendons written into the buffer.

virtual PxU32 getNbSpatialTendons() = 0

Returns the number of spatial tendons in the articulation.

Returns

The number of tendons.

virtual PxU32 getFixedTendons(PxArticulationFixedTendon **userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0

Returns the fixed tendons attached to the articulation.

The order of the tendons in the buffer is not necessarily identical to the order in which the tendons were added to the articulation.

Parameters
  • userBuffer[in] The buffer into which to write the array of pointers to the tendons.

  • bufferSize[in] The size of the buffer. If this is not large enough to contain all the pointers to tendons, only as many as will fit are written. Use getNbFixedTendons to size for all attached tendons.

  • startIndex[in] Index of first tendon pointer to be retrieved.

Returns

The number of tendons written into the buffer.

virtual PxU32 getNbFixedTendons() = 0

Returns the number of fixed tendons in the articulation.

Returns

The number of tendons.

virtual PxU32 getSensors(PxArticulationSensor **userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0

Returns the sensors attached to the articulation.

The order of the sensors in the buffer is not necessarily identical to the order in which the sensors were added to the articulation.

Parameters
  • userBuffer[in] The buffer into which to write the array of pointers to the sensors.

  • bufferSize[in] The size of the buffer. If this is not large enough to contain all the pointers to sensors, only as many as will fit are written. Use getNbSensors to size for all attached sensors.

  • startIndex[in] Index of first sensor pointer to be retrieved.

Returns

The number of sensors written into the buffer.

virtual PxU32 getNbSensors() = 0

Returns the number of sensors in the articulation.

Returns

The number of sensors.

virtual void updateKinematic(PxArticulationKinematicFlags flags) = 0

Update link velocities and/or positions in the articulation.

For performance, prefer the PxArticulationCache API that performs batch articulation state updates.

If the application updates the root state (position and velocity) or joint state via any combination of the non-cache API calls

the application needs to call this method after the state setting in order to update the link states for the next simulation frame or querying.

Use

See also

PxArticulationKinematicFlags, PxArticulationCache, applyCache

Note

This call may only be made on articulations that are in a scene, and may not be made during simulation.

inline virtual ~PxArticulationReducedCoordinate()
virtual const char *getConcreteTypeName() const = 0

Returns string name of dynamic type.

Returns

Class name of most derived type of this object.

template<class T>
inline T *is()
template<class T>
inline const T *is() const
inline PxType getConcreteType() const

Returns concrete type of object.

See also

PxConcreteType

Returns

PxConcreteType::Enum of serialized object

inline void setBaseFlag(PxBaseFlag::Enum flag, bool value)

Set PxBaseFlag

Parameters
  • flag[in] The flag to be set

  • value[in] The flags new value

inline void setBaseFlags(PxBaseFlags inFlags)

Set PxBaseFlags

See also

PxBaseFlags

Parameters

inFlags[in] The flags to be set

inline PxBaseFlags getBaseFlags() const

Returns PxBaseFlags.

See also

PxBaseFlags

Returns

PxBaseFlags

inline virtual bool isReleasable() const

Whether the object is subordinate.

A class is subordinate, if it can only be instantiated in the context of another class.

Returns

Whether the class is subordinate

Public Members

void *userData

user can assign this to whatever, usually to create a 1:1 relationship with a user object.

Protected Functions

inline PxArticulationReducedCoordinate(PxType concreteType, PxBaseFlags baseFlags)
inline PxArticulationReducedCoordinate(PxBaseFlags baseFlags)
inline virtual bool isKindOf(const char *superClass) const

Returns whether a given type name matches with the type of this instance.

template<class T>
inline bool typeMatch() const

Protected Attributes

PxType mConcreteType
PxBaseFlags mBaseFlags
PxU32 mBuiltInRefCount