PxImmediateMode.h
Go to the documentation of this file.
1 //
2 // Redistribution and use in source and binary forms, with or without
3 // modification, are permitted provided that the following conditions
4 // are met:
5 // * Redistributions of source code must retain the above copyright
6 // notice, this list of conditions and the following disclaimer.
7 // * Redistributions in binary form must reproduce the above copyright
8 // notice, this list of conditions and the following disclaimer in the
9 // documentation and/or other materials provided with the distribution.
10 // * Neither the name of NVIDIA CORPORATION nor the names of its
11 // contributors may be used to endorse or promote products derived
12 // from this software without specific prior written permission.
13 //
14 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY
15 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
16 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
17 // PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
18 // CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
19 // EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
20 // PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
21 // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
22 // OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
23 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
24 // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
25 //
26 // Copyright (c) 2008-2021 NVIDIA Corporation. All rights reserved.
27 // Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
28 // Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
29 
30 #ifndef PX_PHYSICS_IMMEDIATE_MODE
31 #define PX_PHYSICS_IMMEDIATE_MODE
32 
35 #include "PxPhysXConfig.h"
36 #include "solver/PxSolverDefs.h"
39 
40 #if !PX_DOXYGEN
41 namespace physx
42 {
43 #endif
44 
45 #if !PX_DOXYGEN
46 namespace immediate
47 {
48 #endif
49 
54  {
55  PX_ALIGN(16, PxVec3 linearVelocity);
67  };
68 
73  {
74  public:
82  virtual bool recordContacts(const Gu::ContactPoint* contactPoints, const PxU32 nbContacts, const PxU32 index) = 0;
83 
84  virtual ~PxContactRecorder(){}
85  };
86 
95  PX_C_EXPORT PX_PHYSX_CORE_API void PxConstructSolverBodies(const PxRigidBodyData* inRigidData, PxSolverBodyData* outSolverBodyData, const PxU32 nbBodies, const PxVec3& gravity, const PxReal dt);
96 
103 
121  PX_C_EXPORT PX_PHYSX_CORE_API PxU32 PxBatchConstraints( const PxSolverConstraintDesc* solverConstraintDescs, const PxU32 nbConstraints, PxSolverBody* solverBodies, const PxU32 nbBodies,
122  PxConstraintBatchHeader* outBatchHeaders, PxSolverConstraintDesc* outOrderedConstraintDescs,
123  Dy::ArticulationV** articulations=NULL, const PxU32 nbArticulations=0);
124 
143  PxConstraintAllocator& allocator, const PxReal invDt, const PxReal bounceThreshold, const PxReal frictionOffsetThreshold, const PxReal correlationDistance);
144 
155  PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateJointConstraints(PxConstraintBatchHeader* batchHeaders, const PxU32 nbHeaders, PxSolverConstraintPrepDesc* jointDescs, PxConstraintAllocator& allocator, const PxReal dt, const PxReal invDt);
156 
169  PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateJointConstraintsWithShaders(PxConstraintBatchHeader* batchHeaders, const PxU32 nbBatchHeaders, PxConstraint** constraints, PxSolverConstraintPrepDesc* jointDescs, PxConstraintAllocator& allocator, const PxReal dt, const PxReal invDt);
170 
172  {
174  const void* constantBlock;
175  };
188  PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateJointConstraintsWithImmediateShaders(PxConstraintBatchHeader* batchHeaders, const PxU32 nbBatchHeaders, PxImmediateConstraint* constraints, PxSolverConstraintPrepDesc* jointDescs, PxConstraintAllocator& allocator, const PxReal dt, const PxReal invDt);
189 
206  PX_C_EXPORT PX_PHYSX_CORE_API void PxSolveConstraints(const PxConstraintBatchHeader* batchHeaders, const PxU32 nbBatchHeaders, const PxSolverConstraintDesc* solverConstraintDescs,
207  const PxSolverBody* solverBodies, PxVec3* linearMotionVelocity, PxVec3* angularMotionVelocity, const PxU32 nbSolverBodies, const PxU32 nbPositionIterations, const PxU32 nbVelocityIterations,
208  const float dt=0.0f, const float invDt=0.0f, const PxU32 nbSolverArticulations=0, Dy::ArticulationV** solverArticulations=NULL);
209 
220  PX_C_EXPORT PX_PHYSX_CORE_API void PxIntegrateSolverBodies(PxSolverBodyData* solverBodyData, PxSolverBody* solverBody, const PxVec3* linearMotionVelocity, const PxVec3* angularMotionState, const PxU32 nbBodiesToIntegrate, const PxReal dt);
221 
242  PX_C_EXPORT PX_PHYSX_CORE_API bool PxGenerateContacts(const PxGeometry* const * geom0, const PxGeometry* const * geom1, const PxTransform* pose0, const PxTransform* pose1, PxCache* contactCache, const PxU32 nbPairs, PxContactRecorder& contactRecorder,
243  const PxReal contactDistance, const PxReal meshContactMargin, const PxReal toleranceLength, PxCacheAllocator& allocator);
244 
252 
254  {
257  };
258 
260  {
269  };
270 
272  {
274  };
275 
277  {
279  float inverseMass;
285  };
286 
287  struct PxLinkData
288  {
292  };
293 
295  {
297 
298  void initData()
299  {
300  inboundJoint.type = PxArticulationJointType::eUNDEFINED; // For root
301  inboundJoint.parentPose = PxTransform(PxIdentity);
302  inboundJoint.childPose = PxTransform(PxIdentity);
303  inboundJoint.frictionCoefficient = 0.05f;
304  inboundJoint.maxJointVelocity = 100.0f;
305 
306  pose = PxTransform(PxIdentity);
307  parent = 0;
308  inverseInertia = PxVec3(1.0f);
309  inverseMass = 1.0f;
310  linearDamping = 0.05f;
311  angularDamping = 0.05f;
312  maxLinearVelocitySq = 100.0f * 100.0f;
313  maxAngularVelocitySq = 50.0f * 50.0f;
314  disableGravity = false;
315 
316  for(PxU32 i=0;i<PxArticulationAxis::eCOUNT;i++)
317  {
318  inboundJoint.motion[i] = PxArticulationMotion::eLOCKED;
319  inboundJoint.limits[i].low = inboundJoint.limits[i].high = 0.0f;
320  inboundJoint.drives[i].stiffness = 0.0f;
321  inboundJoint.drives[i].damping = 0.0f;
322  inboundJoint.drives[i].maxForce = 0.0f;
323  inboundJoint.drives[i].driveType = PxArticulationDriveType::eFORCE;
324  }
325  memset(inboundJoint.targetPos, 0xff, sizeof(PxReal)*PxArticulationAxis::eCOUNT);
326  memset(inboundJoint.targetVel, 0xff, sizeof(PxReal)*PxArticulationAxis::eCOUNT);
327  }
328 
330 
331  // Non-mutable link data
334  };
335 
343  // PT: Design note: I use Dy::ArticulationV* to be consistent with PxSolverDefs.h
345 
352  PX_C_EXPORT PX_PHYSX_CORE_API void PxReleaseArticulation(Dy::ArticulationV* articulation);
353 
362 
363 
373 
382  PX_C_EXPORT PX_PHYSX_CORE_API void PxApplyArticulationCache(Dy::ArticulationV* articulation, PxArticulationCache& cache, PxArticulationCacheFlags flag);
383 
392 
401  PX_C_EXPORT PX_PHYSX_CORE_API Dy::ArticulationLinkHandle PxAddArticulationLink(Dy::ArticulationV* articulation, const PxFeatherstoneArticulationLinkData& data, bool isLastLink=false);
402 
409 
416 
427 
437  PX_C_EXPORT PX_PHYSX_CORE_API PxU32 PxGetAllLinkData(const Dy::ArticulationV* articulation, PxLinkData* data);
438 
448 
458 
468 
478 
485  PX_C_EXPORT PX_PHYSX_CORE_API void PxComputeUnconstrainedVelocities(Dy::ArticulationV* articulation, const PxVec3& gravity, const PxReal dt);
486 
492  PX_C_EXPORT PX_PHYSX_CORE_API void PxUpdateArticulationBodies(Dy::ArticulationV* articulation, const PxReal dt);
493 
503  PX_C_EXPORT PX_PHYSX_CORE_API void PxComputeUnconstrainedVelocitiesTGS(Dy::ArticulationV* articulation, const PxVec3& gravity, const PxReal dt, const PxReal totalDt, const PxReal invDt, const PxReal invTotalDt);
504 
510  PX_C_EXPORT PX_PHYSX_CORE_API void PxUpdateArticulationBodiesTGS(Dy::ArticulationV* articulation, const PxReal dt);
511 
512 
523  PX_C_EXPORT PX_PHYSX_CORE_API void PxConstructSolverBodiesTGS(const PxRigidBodyData* inRigidData, PxTGSSolverBodyVel* outSolverBodyVel, PxTGSSolverBodyTxInertia* outSolverBodyTxInertia, PxTGSSolverBodyData* outSolverBodyData, const PxU32 nbBodies, const PxVec3& gravity, const PxReal dt);
524 
532  PX_C_EXPORT PX_PHYSX_CORE_API void PxConstructStaticSolverBodyTGS(const PxTransform& globalPose, PxTGSSolverBodyVel& solverBodyVel, PxTGSSolverBodyTxInertia& solverBodyTxInertia, PxTGSSolverBodyData& solverBodyData);
533 
551  PX_C_EXPORT PX_PHYSX_CORE_API PxU32 PxBatchConstraintsTGS(const PxSolverConstraintDesc* solverConstraintDescs, const PxU32 nbConstraints, PxTGSSolverBodyVel* solverBodies, const PxU32 nbBodies,
552  PxConstraintBatchHeader* outBatchHeaders, PxSolverConstraintDesc* outOrderedConstraintDescs,
553  Dy::ArticulationV** articulations = NULL, const PxU32 nbArticulations = 0);
554 
555 
575  PxConstraintAllocator& allocator, const PxReal invDt, const PxReal invTotalDt, const PxReal bounceThreshold, const PxReal frictionOffsetThreshold, const PxReal correlationDistance);
576 
591  PxTGSSolverConstraintPrepDesc* jointDescs, PxConstraintAllocator& allocator, const PxReal dt, const PxReal totalDt, const PxReal invDt,
592  const PxReal invTotalDt, const PxReal lengthScale);
593 
609  PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateJointConstraintsWithShadersTGS(PxConstraintBatchHeader* batchHeaders, const PxU32 nbBatchHeaders, PxConstraint** constraints, PxTGSSolverConstraintPrepDesc* jointDescs, PxConstraintAllocator& allocator, const PxReal dt,
610  const PxReal totalDt, const PxReal invDt, const PxReal invTotalDt, const PxReal lengthScale);
611 
629  PxConstraintAllocator& allocator, const PxReal dt, const PxReal totalDt, const PxReal invDt, const PxReal invTotalDt, const PxReal lengthScale);
630 
631 
647  PX_C_EXPORT PX_PHYSX_CORE_API void PxSolveConstraintsTGS(const PxConstraintBatchHeader* batchHeaders, const PxU32 nbBatchHeaders, const PxSolverConstraintDesc* solverConstraintDescs,
648  PxTGSSolverBodyVel* solverBodies, PxTGSSolverBodyTxInertia* txInertias, const PxU32 nbSolverBodies, const PxU32 nbPositionIterations, const PxU32 nbVelocityIterations,
649  const float dt, const float invDt, const PxU32 nbSolverArticulations, Dy::ArticulationV** solverArticulations);
650 
660  PX_C_EXPORT PX_PHYSX_CORE_API void PxIntegrateSolverBodiesTGS(PxTGSSolverBodyVel* solverBody, PxTGSSolverBodyTxInertia* txInertia, PxTransform* poses, const PxU32 nbBodiesToIntegrate, const PxReal dt);
661 
662 
663 #if !PX_DOXYGEN
664 }
665 #endif
666 
667 #if !PX_DOXYGEN
668 }
669 #endif
670 
672 #endif
673 
Definition: GuContactBuffer.h:37
const void * constantBlock
Definition: PxImmediateMode.h:174
Definition: PxSolverDefs.h:302
Definition: PxImmediateMode.h:253
size_t ArticulationLinkHandle
Definition: PxSolverDefs.h:54
PxArticulationFlags flags
Definition: PxImmediateMode.h:273
Definition: PxSolverDefs.h:402
Definition: Px.h:84
PX_C_EXPORT PX_PHYSX_CORE_API void PxUpdateArticulationBodies(Dy::ArticulationV *articulation, const PxReal dt)
Updates bodies for a given articulation.
PX_C_EXPORT PX_PHYSX_CORE_API void PxComputeUnconstrainedVelocitiesTGS(Dy::ArticulationV *articulation, const PxVec3 &gravity, const PxReal dt, const PxReal totalDt, const PxReal invDt, const PxReal invTotalDt)
Computes unconstrained velocities for a given articulation.
Callback class to record contact points produced by immediate::PxGenerateContacts.
Definition: PxImmediateMode.h:72
Definition: PxSolverDefs.h:172
PxU32 pad
96 Padding for 16-byte alignment
Definition: PxImmediateMode.h:66
PX_C_EXPORT PX_PHYSX_CORE_API Dy::ArticulationV * PxCreateFeatherstoneArticulation(const PxFeatherstoneArticulationData &data)
Creates an immediate-mode reduced-coordinate articulation.
Definition: PxSolverDefs.h:80
virtual ~PxContactRecorder()
Definition: PxImmediateMode.h:84
Definition: PxSolverDefs.h:307
PxTransform body2World
76 World space transform
Definition: PxImmediateMode.h:61
PxConstraintSolverPrep prep
Definition: PxImmediateMode.h:173
PxVec3 invInertia
44 Mass-space inverse interia diagonal vector
Definition: PxImmediateMode.h:59
PxU8 nbContacts
Definition: PxContact.h:462
PX_C_EXPORT PX_PHYSX_CORE_API bool PxGetMutableLinkData(const Dy::ArticulationLinkHandle link, PxMutableLinkData &data)
Retrieves mutable link data from a link handle.
PX_C_EXPORT PX_PHYSX_CORE_API void PxApplyArticulationCache(Dy::ArticulationV *articulation, PxArticulationCache &cache, PxArticulationCacheFlags flag)
Apply the user defined data in the cache to the articulation system.
PxVec3 angularVelocity
Definition: PxImmediateMode.h:291
float PxReal
Definition: PxSimpleTypes.h:78
Definition: PxSolverDefs.h:342
PxVec3 linearVelocity
Definition: PxImmediateMode.h:290
PX_C_EXPORT PX_PHYSX_CORE_API void PxConstructStaticSolverBody(const PxTransform &globalPose, PxSolverBodyData &solverBodyData)
Constructs a PxSolverBodyData structure for a static body at a given pose.
Definition: PxSolverDefs.h:336
#define PX_C_EXPORT
Definition: Pxc.h:54
float maxAngularVelocitySq
Definition: PxImmediateMode.h:283
PX_C_EXPORT PX_PHYSX_CORE_API Dy::ArticulationLinkHandle PxAddArticulationLink(Dy::ArticulationV *articulation, const PxFeatherstoneArticulationLinkData &data, bool isLastLink=false)
Adds a link to an immediate-mode reduced-coordinate articulation. The articulation becomes the link&#39;s...
Definition: PxImmediateMode.h:276
PxReal maxAngularVelocitySq
92 Squared maximum angular velocity
Definition: PxImmediateMode.h:65
Enum
Definition: PxSolverDefs.h:255
PxReal angularDamping
84 Angular damping coefficient
Definition: PxImmediateMode.h:63
PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateJointConstraintsTGS(PxConstraintBatchHeader *batchHeaders, const PxU32 nbHeaders, PxTGSSolverConstraintPrepDesc *jointDescs, PxConstraintAllocator &allocator, const PxReal dt, const PxReal totalDt, const PxReal invDt, const PxReal invTotalDt, const 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.
Definition: PxSolverDefs.h:216
PxU32(* PxConstraintSolverPrep)(Px1DConstraint *constraints, PxVec3 &bodyAWorldOffset, PxU32 maxConstraints, PxConstraintInvMassScale &invMassScale, const void *constantBlock, const PxTransform &bodyAToWorld, const PxTransform &bodyBToWorld, bool useExtendedLimits, PxVec3 &cAtW, PxVec3 &cBtW)
Definition: PxConstraintDesc.h:228
PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateJointConstraintsWithImmediateShaders(PxConstraintBatchHeader *batchHeaders, const PxU32 nbBatchHeaders, PxImmediateConstraint *constraints, PxSolverConstraintPrepDesc *jointDescs, PxConstraintAllocator &allocator, const PxReal dt, const PxReal invDt)
Creates a set of joint constraint blocks. This function runs joint shaders defined inside PxImmediate...
#define PX_PHYSX_CORE_API
Definition: PxPhysXCommonConfig.h:59
PxReal maxLinearVelocitySq
88 Squared maximum linear velocity
Definition: PxImmediateMode.h:64
PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateContactConstraintsTGS(PxConstraintBatchHeader *batchHeaders, const PxU32 nbHeaders, PxTGSSolverContactDesc *contactDescs, PxConstraintAllocator &allocator, const PxReal invDt, const PxReal invTotalDt, const PxReal bounceThreshold, const PxReal frictionOffsetThreshold, const 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.
bool disableGravity
Definition: PxImmediateMode.h:284
PX_C_EXPORT PX_PHYSX_CORE_API void PxReleaseArticulationCache(PxArticulationCache &cache)
Release an articulation cache.
PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateContactConstraints(PxConstraintBatchHeader *batchHeaders, const PxU32 nbHeaders, PxSolverContactDesc *contactDescs, PxConstraintAllocator &allocator, const PxReal invDt, const PxReal bounceThreshold, const PxReal frictionOffsetThreshold, const 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.
A geometry object.
Definition: PxGeometry.h:75
PX_C_EXPORT PX_PHYSX_CORE_API void PxReleaseArticulation(Dy::ArticulationV *articulation)
Releases an immediate-mode reduced-coordinate articulation.
PxTransform childPose
Definition: PxImmediateMode.h:256
PX_C_EXPORT PX_PHYSX_CORE_API void PxSolveConstraints(const PxConstraintBatchHeader *batchHeaders, const PxU32 nbBatchHeaders, const PxSolverConstraintDesc *solverConstraintDescs, const PxSolverBody *solverBodies, PxVec3 *linearMotionVelocity, PxVec3 *angularMotionVelocity, const PxU32 nbSolverBodies, const PxU32 nbPositionIterations, const PxU32 nbVelocityIterations, const float dt=0.0f, const float invDt=0.0f, const PxU32 nbSolverArticulations=0, Dy::ArticulationV **solverArticulations=NULL)
Iteratively solves the set of constraints defined by the provided PxConstraintBatchHeader and PxSolve...
Definition: PxArticulationReducedCoordinate.h:77
PX_C_EXPORT PX_PHYSX_CORE_API void PxConstructSolverBodies(const PxRigidBodyData *inRigidData, PxSolverBodyData *outSolverBodyData, const PxU32 nbBodies, const PxVec3 &gravity, const PxReal dt)
Constructs a PxSolverBodyData structure based on rigid body properties. Applies gravity, damping and clamps maximum velocity.
Definition: PxCollisionDefs.h:67
Dy::ArticulationLinkHandle parent
Definition: PxImmediateMode.h:333
float linearDamping
Definition: PxImmediateMode.h:280
float angularDamping
Definition: PxImmediateMode.h:281
PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateJointConstraintsWithShaders(PxConstraintBatchHeader *batchHeaders, const PxU32 nbBatchHeaders, PxConstraint **constraints, PxSolverConstraintPrepDesc *jointDescs, PxConstraintAllocator &allocator, const PxReal dt, const PxReal invDt)
Creates a set of joint constraint blocks. This function runs joint shaders defined inside PxConstrain...
Definition: PxSolverDefs.h:314
PX_C_EXPORT PX_PHYSX_CORE_API PxArticulationCache * PxCreateArticulationCache(Dy::ArticulationV *articulation)
Creates an articulation cache.
Definition: PxImmediateMode.h:259
PX_C_EXPORT PX_PHYSX_CORE_API void PxCopyInternalStateToArticulationCache(Dy::ArticulationV *articulation, PxArticulationCache &cache, PxArticulationCacheFlags flag)
Copy the internal data of the articulation to the cache.
PX_C_EXPORT PX_PHYSX_CORE_API void PxUpdateArticulationBodiesTGS(Dy::ArticulationV *articulation, const PxReal dt)
Updates bodies for a given articulation.
PxArticulationJointType::Enum type
Definition: PxImmediateMode.h:261
PX_C_EXPORT PX_PHYSX_CORE_API bool PxGetLinkData(const Dy::ArticulationLinkHandle link, PxLinkData &data)
Retrieves non-mutable link data from a link handle. The data here is computed by the articulation cod...
PxTransform pose
Definition: PxImmediateMode.h:289
void initData()
Definition: PxImmediateMode.h:298
PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateJointConstraints(PxConstraintBatchHeader *batchHeaders, const PxU32 nbHeaders, PxSolverConstraintPrepDesc *jointDescs, PxConstraintAllocator &allocator, const PxReal dt, const 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.
PxReal maxJointVelocity
Definition: PxImmediateMode.h:268
PxReal invMass
16 Inverse mass
Definition: PxImmediateMode.h:56
PX_C_EXPORT PX_PHYSX_CORE_API bool PxSetMutableLinkData(Dy::ArticulationLinkHandle link, const PxMutableLinkData &data)
Sets mutable link data for given link.
class representing a rigid euclidean transform as a quaternion and a vector
Definition: PxTransform.h:48
A plugin class for implementing constraints.
Definition: PxConstraint.h:108
Definition: PxSolverDefs.h:188
PxVec3 angularVelocity
28 Angular velocity
Definition: PxImmediateMode.h:57
PxReal linearDamping
80 Linear damping coefficient
Definition: PxImmediateMode.h:62
PX_C_EXPORT PX_PHYSX_CORE_API void PxConstructStaticSolverBodyTGS(const PxTransform &globalPose, PxTGSSolverBodyVel &solverBodyVel, PxTGSSolverBodyTxInertia &solverBodyTxInertia, PxTGSSolverBodyData &solverBodyData)
Constructs a PxSolverBodyData structure for a static body at a given pose.
PX_C_EXPORT PX_PHYSX_CORE_API PxU32 PxGetLinkIndex(const Dy::ArticulationLinkHandle link)
Retrieves link index from a link handle.
Definition: PxImmediateMode.h:171
PX_C_EXPORT PX_PHYSX_CORE_API PxU32 PxBatchConstraints(const PxSolverConstraintDesc *solverConstraintDescs, const PxU32 nbConstraints, PxSolverBody *solverBodies, const PxU32 nbBodies, PxConstraintBatchHeader *outBatchHeaders, PxSolverConstraintDesc *outOrderedConstraintDescs, Dy::ArticulationV **articulations=NULL, const PxU32 nbArticulations=0)
Groups together sets of independent PxSolverConstraintDesc objects to be solved using SIMD SOA approa...
PxReal frictionCoefficient
Definition: PxImmediateMode.h:267
Definition: PxSolverDefs.h:63
PxTransform pose
Definition: PxImmediateMode.h:332
PX_C_EXPORT PX_PHYSX_CORE_API bool PxGetJointData(const Dy::ArticulationLinkHandle link, PxFeatherstoneArticulationJointData &data)
Retrieves joint data from a link handle.
Definition: PxImmediateMode.h:294
A structure to cache contact information produced by LL contact gen functions.
Definition: PxCollisionDefs.h:49
float maxLinearVelocitySq
Definition: PxImmediateMode.h:282
PX_C_EXPORT PX_PHYSX_CORE_API void PxIntegrateSolverBodies(PxSolverBodyData *solverBodyData, PxSolverBody *solverBody, const PxVec3 *linearMotionVelocity, const PxVec3 *angularMotionState, const PxU32 nbBodiesToIntegrate, const PxReal dt)
Integrates a rigid body, returning the new velocities and transforms. After this function has been ca...
Structure to store rigid body properties.
Definition: PxImmediateMode.h:53
float inverseMass
Definition: PxImmediateMode.h:279
PX_C_EXPORT PX_PHYSX_CORE_API PxU32 PxGetAllLinkData(const Dy::ArticulationV *articulation, PxLinkData *data)
Retrieves non-mutable link data from an articulation handle (all links). The data here is computed by...
Definition: PxSolverDefs.h:257
PX_C_EXPORT PX_PHYSX_CORE_API Dy::ArticulationV * PxGetLinkArticulation(const Dy::ArticulationLinkHandle link)
Retrieves owner/parent articulation handle from a link handle.
#define PX_ALIGN(alignment, decl)
Definition: PxPreprocessor.h:408
Definition: PxSolverDefs.h:247
Enum
Definition: PxSolverDefs.h:268
PX_C_EXPORT PX_PHYSX_CORE_API PxU32 PxBatchConstraintsTGS(const PxSolverConstraintDesc *solverConstraintDescs, const PxU32 nbConstraints, PxTGSSolverBodyVel *solverBodies, const PxU32 nbBodies, PxConstraintBatchHeader *outBatchHeaders, PxSolverConstraintDesc *outOrderedConstraintDescs, Dy::ArticulationV **articulations=NULL, const PxU32 nbArticulations=0)
Groups together sets of independent PxSolverConstraintDesc objects to be solved using SIMD SOA approa...
PX_C_EXPORT PX_PHYSX_CORE_API bool PxGenerateContacts(const PxGeometry *const *geom0, const PxGeometry *const *geom1, const PxTransform *pose0, const PxTransform *pose1, PxCache *contactCache, const PxU32 nbPairs, PxContactRecorder &contactRecorder, const PxReal contactDistance, const PxReal meshContactMargin, const PxReal toleranceLength, PxCacheAllocator &allocator)
Performs contact generation for a given pair of geometries at the specified poses. Produced contacts are stored in the provided Gu::ContactBuffer. 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&#39;s responsibility to reset the PxCache.
Definition: PxImmediateMode.h:287
PX_C_EXPORT PX_PHYSX_CORE_API bool PxSetJointData(Dy::ArticulationLinkHandle link, const PxFeatherstoneArticulationJointData &data)
Sets joint data for given link.
Definition: PxSolverDefs.h:111
PX_C_EXPORT PX_PHYSX_CORE_API void PxIntegrateSolverBodiesTGS(PxTGSSolverBodyVel *solverBody, PxTGSSolverBodyTxInertia *txInertia, PxTransform *poses, const PxU32 nbBodiesToIntegrate, const PxReal dt)
Integrates a rigid body, returning the new velocities and transforms. After this function has been ca...
PxFeatherstoneArticulationLinkData()
Definition: PxImmediateMode.h:296
PX_C_EXPORT PX_PHYSX_CORE_API void PxComputeUnconstrainedVelocities(Dy::ArticulationV *articulation, const PxVec3 &gravity, const PxReal dt)
Computes unconstrained velocities for a given articulation.
PxReal maxDepenetrationVelocity
32 Maximum de-penetration velocity
Definition: PxImmediateMode.h:58
uint32_t PxU32
Definition: Px.h:48
PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateJointConstraintsWithImmediateShadersTGS(PxConstraintBatchHeader *batchHeaders, const PxU32 nbBatchHeaders, PxImmediateConstraint *constraints, PxTGSSolverConstraintPrepDesc *jointDescs, PxConstraintAllocator &allocator, const PxReal dt, const PxReal totalDt, const PxReal invDt, const PxReal invTotalDt, const PxReal lengthScale)
Creates a set of joint constraint blocks. This function runs joint shaders defined inside PxImmediate...
Definition: PxSolverDefs.h:383
PX_C_EXPORT PX_PHYSX_CORE_API void PxRegisterImmediateArticulations()
Register articulation-related solver functions. This is equivalent to PxRegisterArticulationsReducedC...
PxTransform parentPose
Definition: PxImmediateMode.h:255
Definition: PxSolverDefs.h:274
Definition: PxSolverDefs.h:294
PX_C_EXPORT PX_PHYSX_CORE_API void PxSolveConstraintsTGS(const PxConstraintBatchHeader *batchHeaders, const PxU32 nbBatchHeaders, const PxSolverConstraintDesc *solverConstraintDescs, PxTGSSolverBodyVel *solverBodies, PxTGSSolverBodyTxInertia *txInertias, const PxU32 nbSolverBodies, const PxU32 nbPositionIterations, const PxU32 nbVelocityIterations, const float dt, const float invDt, const PxU32 nbSolverArticulations, Dy::ArticulationV **solverArticulations)
Iteratively solves the set of constraints defined by the provided PxConstraintBatchHeader and PxSolve...
PxFeatherstoneArticulationJointData inboundJoint
Definition: PxImmediateMode.h:329
PX_C_EXPORT PX_PHYSX_CORE_API void PxConstructSolverBodiesTGS(const PxRigidBodyData *inRigidData, PxTGSSolverBodyVel *outSolverBodyVel, PxTGSSolverBodyTxInertia *outSolverBodyTxInertia, PxTGSSolverBodyData *outSolverBodyData, const PxU32 nbBodies, const PxVec3 &gravity, const PxReal dt)
Constructs a PxSolverBodyData structure based on rigid body properties. Applies gravity, damping and clamps maximum velocity.
PxVec3 inverseInertia
Definition: PxImmediateMode.h:278
PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateJointConstraintsWithShadersTGS(PxConstraintBatchHeader *batchHeaders, const PxU32 nbBatchHeaders, PxConstraint **constraints, PxTGSSolverConstraintPrepDesc *jointDescs, PxConstraintAllocator &allocator, const PxReal dt, const PxReal totalDt, const PxReal invDt, const PxReal invTotalDt, const PxReal lengthScale)
Creates a set of joint constraint blocks. This function runs joint shaders defined inside PxConstrain...
3 Element vector class.
Definition: PxVec3.h:49
Definition: PxImmediateMode.h:271
Definition: PxSolverDefs.h:104
PxReal maxContactImpulse
48 Maximum permissable contact impulse
Definition: PxImmediateMode.h:60