Immediatemode

Classes

  • PxContactRecorder: Callback class to record contact points produced by immediate::PxGenerateContacts.

Functions

Structs

Typedefs

Functions

PxArticulationLinkCookie PxAddArticulationLink(PxArticulationCookie articulation, const PxArticulationLinkCookie *parent, const PxArticulationLinkDataRC &data)

Add a link to the articulation.

All links must be added before the articulation is completed. It is not possible to add a new link at runtime.

Returned cookie is a temporary ID for the link, only valid until PxEndCreateArticulationRC is called.

Parameters
  • articulation[in] Cookie value returned by PxBeginCreateArticulationRC

  • parent[in] Parent for the new link, or NULL if this is the root link

  • data[in] Link data

Returns

Link cookie

void PxApplyArticulationCache(PxArticulationHandle articulation, PxArticulationCache &cache, PxArticulationCacheFlags flag)

Apply the user defined data in the cache to the articulation system.

Parameters
  • articulation[in] Articulation handle.

  • cache[in] Articulation data.

  • flag[in] Defines which values in the cache will be applied to the articulation

PxU32 PxBatchConstraints(const PxSolverConstraintDesc *solverConstraintDescs, PxU32 nbConstraints, PxSolverBody *solverBodies, PxU32 nbBodies, PxConstraintBatchHeader *outBatchHeaders, PxSolverConstraintDesc *outOrderedConstraintDescs, PxArticulationHandle *articulations = NULL, PxU32 nbArticulations = 0)

Groups together sets of independent PxSolverConstraintDesc objects to be solved using SIMD SOA approach.

Note

This method considers all bodies within the range [0, nbBodies-1] to be valid dynamic bodies. A given dynamic body can only be referenced in a batch once. Static or kinematic bodies can be referenced multiple times within a batch safely because constraints do not affect their velocities. The batching will implicitly consider any bodies outside of the range [0, nbBodies-1] to be infinite mass (static or kinematic). This means that either appending static/kinematic to the end of the array of bodies or placing static/kinematic bodies at before the start body pointer will ensure that the minimum number of batches are produced.

Parameters
  • solverConstraintDescs[in] The set of solver constraint descs to batch

  • nbConstraints[in] The number of constraints to batch

  • solverBodies[inout] The array of solver bodies that the constraints reference. Some fields in these structures are written to as scratch memory for the batching.

  • nbBodies[in] The number of bodies

  • outBatchHeaders[out] The batch headers produced by this batching process. This array must have at least 1 entry per input constraint

  • outOrderedConstraintDescs[out] A reordered copy of the constraint descs. This array is referenced by the constraint batches. This array must have at least 1 entry per input constraint.

  • articulations[inout] The array of articulations that the constraints reference. Some fields in these structures are written to as scratch memory for the batching.

  • nbArticulations[in] The number of articulations

Returns

The total number of batches produced. This should be less than or equal to nbConstraints.

PxU32 PxBatchConstraintsTGS(const PxSolverConstraintDesc *solverConstraintDescs, PxU32 nbConstraints, PxTGSSolverBodyVel *solverBodies, PxU32 nbBodies, PxConstraintBatchHeader *outBatchHeaders, PxSolverConstraintDesc *outOrderedConstraintDescs, PxArticulationHandle *articulations = NULL, PxU32 nbArticulations = 0)

Groups together sets of independent PxSolverConstraintDesc objects to be solved using SIMD SOA approach.

Note

This method considers all bodies within the range [0, nbBodies-1] to be valid dynamic bodies. A given dynamic body can only be referenced in a batch once. Static or kinematic bodies can be referenced multiple times within a batch safely because constraints do not affect their velocities. The batching will implicitly consider any bodies outside of the range [0, nbBodies-1] to be infinite mass (static or kinematic). This means that either appending static/kinematic to the end of the array of bodies or placing static/kinematic bodies at before the start body pointer will ensure that the minimum number of batches are produced.

Parameters
  • solverConstraintDescs[in] The set of solver constraint descs to batch

  • nbConstraints[in] The number of constraints to batch

  • solverBodies[inout] The array of solver bodies that the constraints reference. Some fields in these structures are written to as scratch memory for the batching.

  • nbBodies[in] The number of bodies

  • outBatchHeaders[out] The batch headers produced by this batching process. This array must have at least 1 entry per input constraint

  • outOrderedConstraintDescs[out] A reordered copy of the constraint descs. This array is referenced by the constraint batches. This array must have at least 1 entry per input constraint.

  • articulations[inout] The array of articulations that the constraints reference. Some fields in these structures are written to as scratch memory for the batching.

  • nbArticulations[in] The number of articulations

Returns

The total number of batches produced. This should be less than or equal to nbConstraints.

PxArticulationCookie PxBeginCreateArticulationRC(const PxArticulationDataRC &data)

Begin creation of an immediate-mode reduced-coordinate articulation.

Returned cookie must be used to add links to the articulation, and to complete creating the articulation.

The cookie is a temporary ID for the articulation, only valid until PxEndCreateArticulationRC is called.

Parameters

data[in] Articulation data

Returns

Articulation cookie

void PxComputeUnconstrainedVelocities(PxArticulationHandle articulation, const PxVec3 &gravity, PxReal dt, PxReal invLengthScale)

Computes unconstrained velocities for a given articulation.

Parameters
  • articulation[in] Articulation handle

  • gravity[in] Gravity vector

  • dt[in] Timestep

  • invLengthScale[in] 1/lengthScale from PxTolerancesScale.

void PxComputeUnconstrainedVelocitiesTGS(PxArticulationHandle articulation, const PxVec3 &gravity, PxReal dt, PxReal totalDt, PxReal invDt, PxReal invTotalDt, PxReal invLengthScale)

Computes unconstrained velocities for a given articulation.

Parameters
  • articulation[in] Articulation handle

  • gravity[in] Gravity vector

  • dt[in] Timestep/numPosIterations

  • totalDt[in] Timestep

  • invDt[in] 1/(Timestep/numPosIterations)

  • invTotalDt[in] 1/Timestep

  • invLengthScale[in] 1/lengthScale from PxTolerancesScale.

void PxConstructSolverBodies(const PxRigidBodyData *inRigidData, PxSolverBodyData *outSolverBodyData, PxU32 nbBodies, const PxVec3 &gravity, PxReal dt, bool gyroscopicForces = false)

Constructs a PxSolverBodyData structure based on rigid body properties.

Applies gravity, damping and clamps maximum velocity.

Parameters
  • inRigidData[in] The array rigid body properties

  • outSolverBodyData[out] The array of solverBodyData produced to represent these bodies

  • nbBodies[in] The total number of solver bodies to create

  • gravity[in] The gravity vector

  • dt[in] The timestep

  • gyroscopicForces[in] Indicates whether gyroscopic forces should be integrated

void PxConstructSolverBodiesTGS(const PxRigidBodyData *inRigidData, PxTGSSolverBodyVel *outSolverBodyVel, PxTGSSolverBodyTxInertia *outSolverBodyTxInertia, PxTGSSolverBodyData *outSolverBodyData, PxU32 nbBodies, const PxVec3 &gravity, PxReal dt, bool gyroscopicForces = false)

Constructs a PxSolverBodyData structure based on rigid body properties.

Applies gravity, damping and clamps maximum velocity.

Parameters
  • inRigidData[in] The array rigid body properties

  • outSolverBodyVel[out] The array of PxTGSSolverBodyVel structures produced to represent these bodies

  • outSolverBodyTxInertia[out] The array of PxTGSSolverBodyTxInertia produced to represent these bodies

  • outSolverBodyData[out] The array of PxTGSolverBodyData produced to represent these bodies

  • nbBodies[in] The total number of solver bodies to create

  • gravity[in] The gravity vector

  • dt[in] The timestep

  • gyroscopicForces[in] Indicates whether gyroscopic forces should be integrated

void PxConstructStaticSolverBody(const PxTransform &globalPose, PxSolverBodyData &solverBodyData)

Constructs a PxSolverBodyData structure for a static body at a given pose.

Parameters
  • globalPose[in] The pose of this static actor

  • solverBodyData[out] The solver body representation of this static actor

void PxConstructStaticSolverBodyTGS(const PxTransform &globalPose, PxTGSSolverBodyVel &solverBodyVel, PxTGSSolverBodyTxInertia &solverBodyTxInertia, PxTGSSolverBodyData &solverBodyData)

Constructs a PxSolverBodyData structure for a static body at a given pose.

Parameters
  • globalPose[in] The pose of this static actor

  • solverBodyVel[out] The velocity component of this body (will be zero)

  • solverBodyTxInertia[out] The intertia and transform delta component of this body (will be zero)

  • solverBodyData[out] The solver body representation of this static actor

void PxCopyInternalStateToArticulationCache(PxArticulationHandle articulation, PxArticulationCache &cache, PxArticulationCacheFlags flag)

Copy the internal data of the articulation to the cache.

See also

createCache PxApplyArticulationCache

Parameters
  • articulation[in] Articulation handle.

  • cache[in] Articulation data

  • flag[in] Indicates which values of the articulation system are copied to the cache

PxArticulationCache *PxCreateArticulationCache(PxArticulationHandle articulation)

Creates an articulation cache.

Parameters

articulation[in] Articulation handle

Returns

Articulation cache

bool PxCreateContactConstraints(PxConstraintBatchHeader *batchHeaders, PxU32 nbHeaders, PxSolverContactDesc *contactDescs, PxConstraintAllocator &allocator, PxReal invDt, PxReal bounceThreshold, PxReal frictionOffsetThreshold, PxReal correlationDistance, PxSpatialVector *Z = NULL)

Creates a set of contact constraint blocks.

Note that, depending the results of PxBatchConstraints, each batchHeader may refer to up to 4 solverConstraintDescs. This function will allocate both constraint and friction patch data via the PxConstraintAllocator provided. Constraint data is only valid until PxSolveConstraints has completed. Friction data is to be retained and provided by the application for friction correlation.

Parameters
  • batchHeaders[in] Array of batch headers to process

  • nbHeaders[in] The total number of headers

  • contactDescs[in] An array of contact descs defining the pair and contact properties of each respective contacting pair

  • allocator[in] An allocator callback to allocate constraint and friction memory

  • invDt[in] The inverse timestep

  • bounceThreshold[in] The bounce threshold. Relative velocities below this will be solved by bias only. Relative velocities above this will be solved by restitution. If restitution is zero then these pairs will always be solved by bias.

  • frictionOffsetThreshold[in] The friction offset threshold. Contacts whose separations are below this threshold can generate friction constraints.

  • correlationDistance[in] The correlation distance used by friction correlation to identify whether a friction patch is broken on the grounds of relation separation.

  • Z[out] Temporary buffer for impulse propagation.

Returns

a boolean to define if this method was successful or not.

bool PxCreateContactConstraintsTGS(PxConstraintBatchHeader *batchHeaders, PxU32 nbHeaders, PxTGSSolverContactDesc *contactDescs, PxConstraintAllocator &allocator, PxReal invDt, PxReal invTotalDt, PxReal bounceThreshold, PxReal frictionOffsetThreshold, PxReal correlationDistance)

Creates a set of contact constraint blocks.

Note that, depending the results of PxBatchConstraints, each batchHeader may refer to up to 4 solverConstraintDescs. This function will allocate both constraint and friction patch data via the PxConstraintAllocator provided. Constraint data is only valid until PxSolveConstraints has completed. Friction data is to be retained and provided by the application for friction correlation.

Parameters
  • batchHeaders[in] Array of batch headers to process

  • nbHeaders[in] The total number of headers

  • contactDescs[in] An array of contact descs defining the pair and contact properties of each respective contacting pair

  • allocator[in] An allocator callback to allocate constraint and friction memory

  • invDt[in] The inverse timestep/nbPositionIterations

  • invTotalDt[in] The inverse time-step

  • bounceThreshold[in] The bounce threshold. Relative velocities below this will be solved by bias only. Relative velocities above this will be solved by restitution. If restitution is zero then these pairs will always be solved by bias.

  • frictionOffsetThreshold[in] The friction offset threshold. Contacts whose separations are below this threshold can generate friction constraints.

  • correlationDistance[in] The correlation distance used by friction correlation to identify whether a friction patch is broken on the grounds of relation separation.

Returns

a boolean to define if this method was successful or not.

bool PxCreateJointConstraints(PxConstraintBatchHeader *batchHeaders, PxU32 nbHeaders, PxSolverConstraintPrepDesc *jointDescs, PxConstraintAllocator &allocator, PxSpatialVector *Z, PxReal dt, PxReal invDt)

Creates a set of joint constraint blocks.

Note that, depending the results of PxBatchConstraints, the batchHeader may refer to up to 4 solverConstraintDescs

Parameters
  • batchHeaders[in] The array of batch headers to be processed.

  • nbHeaders[in] The total number of batch headers to process.

  • jointDescs[in] An array of constraint prep descs defining the properties of the constraints being created.

  • allocator[in] An allocator callback to allocate constraint data.

  • dt[in] The timestep.

  • invDt[in] The inverse timestep.

  • Z[out] Temporary buffer for impulse propagation.

Returns

a boolean indicating if this method was successful or not.

bool PxCreateJointConstraintsTGS(PxConstraintBatchHeader *batchHeaders, PxU32 nbHeaders, PxTGSSolverConstraintPrepDesc *jointDescs, PxConstraintAllocator &allocator, PxReal dt, PxReal totalDt, PxReal invDt, PxReal invTotalDt, PxReal lengthScale)

Creates a set of joint constraint blocks.

Note that, depending the results of PxBatchConstraints, the batchHeader may refer to up to 4 solverConstraintDescs

Parameters
  • batchHeaders[in] The array of batch headers to be processed

  • nbHeaders[in] The total number of batch headers to process

  • jointDescs[in] An array of constraint prep descs defining the properties of the constraints being created

  • allocator[in] An allocator callback to allocate constraint data

  • dt[in] The total time-step/nbPositionIterations

  • totalDt[in] The total time-step

  • invDt[in] The inverse (timestep/nbPositionIterations)

  • invTotalDt[in] The inverse total time-step

  • lengthScale[in] PxToleranceScale::length, i.e. a meter in simulation units

Returns

a boolean indicating if this method was successful or not.

bool PxCreateJointConstraintsWithImmediateShaders(PxConstraintBatchHeader *batchHeaders, PxU32 nbBatchHeaders, PxImmediateConstraint *constraints, PxSolverConstraintPrepDesc *jointDescs, PxConstraintAllocator &allocator, PxReal dt, PxReal invDt, PxSpatialVector *Z = NULL)

Creates a set of joint constraint blocks.

This function runs joint shaders defined inside PxImmediateConstraint* param, fills in joint row information in jointDescs and then calls PxCreateJointConstraints.

Parameters
  • batchHeaders[in] The set of batchHeaders to be processed.

  • nbBatchHeaders[in] The number of batch headers to process.

  • constraints[in] The set of constraints to be used to produce constraint rows.

  • jointDescs[inout] An array of constraint prep descs defining the properties of the constraints being created.

  • allocator[in] An allocator callback to allocate constraint data.

  • dt[in] The timestep.

  • invDt[in] The inverse timestep.

  • Z[out] Temporary buffer for impulse propagation.

Returns

a boolean indicating if this method was successful or not.

bool PxCreateJointConstraintsWithImmediateShadersTGS(PxConstraintBatchHeader *batchHeaders, PxU32 nbBatchHeaders, PxImmediateConstraint *constraints, PxTGSSolverConstraintPrepDesc *jointDescs, PxConstraintAllocator &allocator, PxReal dt, PxReal totalDt, PxReal invDt, PxReal invTotalDt, PxReal lengthScale)

Creates a set of joint constraint blocks.

This function runs joint shaders defined inside PxImmediateConstraint* param, fills in joint row information in jointDescs and then calls PxCreateJointConstraints.

Parameters
  • batchHeaders[in] The set of batchHeaders to be processed

  • nbBatchHeaders[in] The number of batch headers to process.

  • constraints[in] The set of constraints to be used to produce constraint rows

  • jointDescs[inout] An array of constraint prep descs defining the properties of the constraints being created

  • allocator[in] An allocator callback to allocate constraint data

  • dt[in] The total time-step/nbPositionIterations

  • totalDt[in] The total time-step

  • invDt[in] The inverse (timestep/nbPositionIterations)

  • invTotalDt[in] The inverse total time-step

  • lengthScale[in] PxToleranceScale::length, i.e. a meter in simulation units

Returns

a boolean indicating if this method was successful or not.

bool PxCreateJointConstraintsWithShaders(PxConstraintBatchHeader *batchHeaders, PxU32 nbBatchHeaders, PxConstraint **constraints, PxSolverConstraintPrepDesc *jointDescs, PxConstraintAllocator &allocator, PxReal dt, PxReal invDt, PxSpatialVector *Z = NULL)

Creates a set of joint constraint blocks.

This function runs joint shaders defined inside PxConstraint** param, fills in joint row information in jointDescs and then calls PxCreateJointConstraints.

Parameters
  • batchHeaders[in] The set of batchHeaders to be processed.

  • nbBatchHeaders[in] The number of batch headers to process.

  • constraints[in] The set of constraints to be used to produce constraint rows.

  • jointDescs[inout] An array of constraint prep descs defining the properties of the constraints being created.

  • allocator[in] An allocator callback to allocate constraint data.

  • dt[in] The timestep.

  • invDt[in] The inverse timestep.

  • Z[out] Temporary buffer for impulse propagation.

Returns

a boolean indicating if this method was successful or not.

bool PxCreateJointConstraintsWithShadersTGS(PxConstraintBatchHeader *batchHeaders, PxU32 nbBatchHeaders, PxConstraint **constraints, PxTGSSolverConstraintPrepDesc *jointDescs, PxConstraintAllocator &allocator, PxReal dt, PxReal totalDt, PxReal invDt, PxReal invTotalDt, PxReal lengthScale)

Creates a set of joint constraint blocks.

This function runs joint shaders defined inside PxConstraint** param, fills in joint row information in jointDescs and then calls PxCreateJointConstraints.

Parameters
  • batchHeaders[in] The set of batchHeaders to be processed

  • nbBatchHeaders[in] The number of batch headers to process.

  • constraints[in] The set of constraints to be used to produce constraint rows

  • jointDescs[inout] An array of constraint prep descs defining the properties of the constraints being created

  • allocator[in] An allocator callback to allocate constraint data

  • dt[in] The total time-step/nbPositionIterations

  • totalDt[in] The total time-step

  • invDt[in] The inverse (timestep/nbPositionIterations)

  • invTotalDt[in] The inverse total time-step

  • lengthScale[in] PxToleranceScale::length, i.e. a meter in simulation units

Returns

a boolean indicating if this method was successful or not.

PxArticulationHandle PxEndCreateArticulationRC(PxArticulationCookie articulation, PxArticulationLinkHandle *linkHandles, PxU32 bufferSize)

End creation of an immediate-mode reduced-coordinate articulation.

This call completes the creation of the articulation. All involved cookies become unsafe to use after that point.

The links are actually created in this function, and it returns the actual link handles to users. The given buffer should be large enough to contain as many links as created between the PxBeginCreateArticulationRC & PxEndCreateArticulationRC calls, i.e. if N calls were made to PxAddArticulationLink, the buffer should be large enough to contain N handles.

Parameters
  • articulation[in] Cookie value returned by PxBeginCreateArticulationRC

  • linkHandles[out] Articulation link handles of all created articulation links

  • bufferSize[in] Size of linkHandles buffer. Must match internal expected number of articulation links.

Returns

Articulation handle, or NULL if creation failed

bool PxGenerateContacts(const PxGeometry *const *geom0, const PxGeometry *const *geom1, const PxTransform *pose0, const PxTransform *pose1, PxCache *contactCache, PxU32 nbPairs, PxContactRecorder &contactRecorder, PxReal contactDistance, PxReal meshContactMargin, PxReal toleranceLength, PxCacheAllocator &allocator)

Performs contact generation for a given pair of geometries at the specified poses.

Produced contacts are stored in the provided contact recorder. Information is cached in PxCache structure to accelerate future contact generation between pairs. This cache data is valid only as long as the memory provided by PxCacheAllocator has not been released/re-used. Recommendation is to retain that data for a single simulation frame, discarding cached data after 2 frames. If the cached memory has been released/re-used prior to the corresponding pair having contact generation performed again, it is the application’s responsibility to reset the PxCache.

Parameters
  • geom0[in] Array of geometries to perform collision detection on.

  • geom1[in] Array of geometries to perform collision detection on

  • pose0[in] Array of poses associated with the corresponding entry in the geom0 array

  • pose1[in] Array of poses associated with the corresponding entry in the geom1 array

  • contactCache[inout] Array of contact caches associated with each pair geom0[i] + geom1[i]

  • nbPairs[in] The total number of pairs to process

  • contactRecorder[out] A callback that is called to record contacts for each pair that detects contacts

  • contactDistance[in] The distance at which contacts begin to be generated between the pairs

  • meshContactMargin[in] The mesh contact margin.

  • toleranceLength[in] The toleranceLength. Used for scaling distance-based thresholds internally to produce appropriate results given simulations in different units

  • allocator[in] A callback to allocate memory for the contact cache

Returns

a boolean indicating if the function was successful or not.

PxU32 PxGetAllLinkData(const PxArticulationHandle articulation, PxArticulationLinkDerivedDataRC *data)

Retrieves non-mutable link data from an articulation handle (all links).

The data here is computed by the articulation code but cannot be directly changed by users.

See also

PxGetLinkData

Parameters
  • articulation[in] Articulation handle

  • data[out] Link data for N links, or NULL to just retrieve the number of links.

Returns

Number of links in the articulation = number of link data structure written to the data array.

bool PxGetJointData(const PxArticulationLinkHandle &link, PxArticulationJointDataRC &data)

Retrieves joint data from a link handle.

See also

PxSetJointData

Parameters
  • link[in] Link handle

  • data[out] Joint data for this link

Returns

True if success

bool PxGetLinkData(const PxArticulationLinkHandle &link, PxArticulationLinkDerivedDataRC &data)

Retrieves non-mutable link data from a link handle.

The data here is computed by the articulation code but cannot be directly changed by users.

See also

PxGetAllLinkData

Parameters
  • link[in] Link handle

  • data[out] Link data

Returns

True if success

bool PxGetMutableLinkData(const PxArticulationLinkHandle &link, PxArticulationLinkMutableDataRC &data)

Retrieves mutable link data from a link handle.

Parameters
  • link[in] Link handle

  • data[out] Data for this link

Returns

True if success

void PxIntegrateSolverBodies(PxSolverBodyData *solverBodyData, PxSolverBody *solverBody, const PxVec3 *linearMotionVelocity, const PxVec3 *angularMotionState, PxU32 nbBodiesToIntegrate, PxReal dt)

Integrates a rigid body, returning the new velocities and transforms.

After this function has been called, solverBodyData stores all the body’s velocity data.

Parameters
  • solverBodyData[inout] The array of solver body data to be integrated

  • solverBody[in] The bodies’ linear and angular velocities

  • linearMotionVelocity[in] The bodies’ linear motion velocity array

  • angularMotionState[in] The bodies’ angular motion velocity array

  • nbBodiesToIntegrate[in] The total number of bodies to integrate

  • dt[in] The timestep

void PxIntegrateSolverBodiesTGS(PxTGSSolverBodyVel *solverBody, PxTGSSolverBodyTxInertia *txInertia, PxTransform *poses, PxU32 nbBodiesToIntegrate, PxReal dt)

Integrates a rigid body, returning the new velocities and transforms.

After this function has been called, solverBody stores all the body’s velocity data.

Parameters
  • solverBody[inout] The array of solver bodies to be integrated

  • txInertia[in] The delta pose and inertia terms

  • poses[inout] The original poses of the bodies. Updated to be the new poses of the bodies

  • nbBodiesToIntegrate[in] The total number of bodies to integrate

  • dt[in] The timestep

void PxReleaseArticulation(PxArticulationHandle articulation)

Releases an immediate-mode reduced-coordinate articulation.

See also

PxCreateFeatherstoneArticulation

Parameters

articulation[in] Articulation handle

void PxReleaseArticulationCache(PxArticulationCache &cache)

Release an articulation cache.

Parameters

cache[in] The cache to release

bool PxSetJointData(const PxArticulationLinkHandle &link, const PxArticulationJointDataRC &data)

Sets joint data for given link.

See also

PxGetJointData

Parameters
  • link[in] Link handle

  • data[in] Joint data for this link

Returns

True if success

bool PxSetMutableLinkData(const PxArticulationLinkHandle &link, const PxArticulationLinkMutableDataRC &data)

Sets mutable link data for given link.

Parameters
  • link[in] Link handle

  • data[in] Data for this link

Returns

True if success

void PxSolveConstraints(const PxConstraintBatchHeader *batchHeaders, PxU32 nbBatchHeaders, const PxSolverConstraintDesc *solverConstraintDescs, const PxSolverBody *solverBodies, PxVec3 *linearMotionVelocity, PxVec3 *angularMotionVelocity, PxU32 nbSolverBodies, PxU32 nbPositionIterations, PxU32 nbVelocityIterations, float dt = 0.0f, float invDt = 0.0f, PxU32 nbSolverArticulations = 0, PxArticulationHandle *solverArticulations = NULL, PxSpatialVector *Z = NULL, PxSpatialVector *deltaV = NULL)

Iteratively solves the set of constraints defined by the provided PxConstraintBatchHeader and PxSolverConstraintDesc structures.

Updates deltaVelocities inside the PxSolverBody structures. Produces resulting linear and angular motion velocities.

Parameters
  • batchHeaders[in] The set of batch headers to be solved

  • nbBatchHeaders[in] The total number of batch headers to be solved

  • solverConstraintDescs[in] The reordererd set of solver constraint descs referenced by the batch headers

  • solverBodies[inout] The set of solver bodies the bodies reference

  • linearMotionVelocity[out] The resulting linear motion velocity

  • angularMotionVelocity[out] The resulting angular motion velocity.

  • nbSolverBodies[in] The total number of solver bodies

  • nbPositionIterations[in] The number of position iterations to run

  • nbVelocityIterations[in] The number of velocity iterations to run

  • dt[in] Timestep. Only needed if articulations are sent to the function.

  • invDt[in] Inverse timestep. Only needed if articulations are sent to the function.

  • nbSolverArticulations[in] Number of articulations to solve constraints for.

  • solverArticulations[in] Array of articulations to solve constraints for.

  • Z[out] Temporary buffer for impulse propagation

  • deltaV[out] Temporary buffer for velocity change

void PxSolveConstraintsTGS(const PxConstraintBatchHeader *batchHeaders, PxU32 nbBatchHeaders, const PxSolverConstraintDesc *solverConstraintDescs, PxTGSSolverBodyVel *solverBodies, PxTGSSolverBodyTxInertia *txInertias, PxU32 nbSolverBodies, PxU32 nbPositionIterations, PxU32 nbVelocityIterations, float dt, float invDt, PxU32 nbSolverArticulations = 0, PxArticulationHandle *solverArticulations = NULL, PxSpatialVector *Z = NULL, PxSpatialVector *deltaV = NULL)

Iteratively solves the set of constraints defined by the provided PxConstraintBatchHeader and PxSolverConstraintDesc structures.

Updates deltaVelocities inside the PxSolverBody structures. Produces resulting linear and angular motion velocities.

Parameters
  • batchHeaders[in] The set of batch headers to be solved

  • nbBatchHeaders[in] The total number of batch headers to be solved

  • solverConstraintDescs[in] The reordererd set of solver constraint descs referenced by the batch headers

  • solverBodies[inout] The set of solver bodies the bodies reference

  • txInertias[inout] The set of solver body TxInertias the bodies reference

  • nbSolverBodies[in] The total number of solver bodies

  • nbPositionIterations[in] The number of position iterations to run

  • nbVelocityIterations[in] The number of velocity iterations to run

  • dt[in] time-step/nbPositionIterations

  • invDt[in] 1/(time-step/nbPositionIterations)

  • nbSolverArticulations[in] Number of articulations to solve constraints for.

  • solverArticulations[in] Array of articulations to solve constraints for.

  • Z[out] Temporary buffer for impulse propagation (only if articulations are used, size should be at least as large as the maximum number of links in any articulations being simulated)

  • deltaV[out] Temporary buffer for velocity change (only if articulations are used, size should be at least as large as the maximum number of links in any articulations being simulated)

void PxUpdateArticulationBodies(PxArticulationHandle articulation, PxReal dt)

Updates bodies for a given articulation.

Parameters
  • articulation[in] Articulation handle

  • dt[in] Timestep

void PxUpdateArticulationBodiesTGS(PxArticulationHandle articulation, PxReal dt)

Updates bodies for a given articulation.

Parameters
  • articulation[in] Articulation handle

  • dt[in] Timestep

Typedefs

typedef void *PxArticulationCookie
typedef void *PxArticulationHandle