Program Listing for include/PxImmediateMode.h

↰ Return to documentation for include/PxImmediateMode.h

// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//  * Redistributions of source code must retain the above copyright
//    notice, this list of conditions and the following disclaimer.
//  * Redistributions in binary form must reproduce the above copyright
//    notice, this list of conditions and the following disclaimer in the
//    documentation and/or other materials provided with the distribution.
//  * Neither the name of NVIDIA CORPORATION nor the names of its
//    contributors may be used to endorse or promote products derived
//    from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY
// EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
// PURPOSE ARE DISCLAIMED.  IN NO EVENT SHALL THE COPYRIGHT OWNER OR
// CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
// EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
// PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
// OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
// Copyright (c) 2008-2022 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.

#ifndef PX_IMMEDIATE_MODE_H
#define PX_IMMEDIATE_MODE_H

#include "PxPhysXConfig.h"
#include "foundation/PxMemory.h"
#include "solver/PxSolverDefs.h"
#include "collision/PxCollisionDefs.h"
#include "PxArticulationReducedCoordinate.h"

#if !PX_DOXYGEN
namespace physx
{
#endif

    class PxCudaContextManager;
    class PxBaseTask;
    class PxGeometry;

#if !PX_DOXYGEN
namespace immediate
{
#endif

    typedef void* PxArticulationHandle;

    struct PxSpatialVector
    {
        PxVec3 top;
        PxReal pad0;
        PxVec3 bottom;
        PxReal pad1;
    };

    struct PxRigidBodyData
    {
        PX_ALIGN(16, PxVec3 linearVelocity);
        PxReal invMass;
        PxVec3 angularVelocity;
        PxReal maxDepenetrationVelocity;
        PxVec3 invInertia;
        PxReal maxContactImpulse;
        PxTransform body2World;
        PxReal linearDamping;
        PxReal angularDamping;
        PxReal maxLinearVelocitySq;
        PxReal maxAngularVelocitySq;
        PxU32 pad;
    };

    class PxContactRecorder
    {
    public:
        virtual bool recordContacts(const PxContactPoint* contactPoints, const PxU32 nbContacts, const PxU32 index) = 0;

        virtual ~PxContactRecorder(){}
    };

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

    PX_C_EXPORT PX_PHYSX_CORE_API void PxConstructStaticSolverBody(const PxTransform& globalPose, PxSolverBodyData& solverBodyData);

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

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

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

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

    struct PxImmediateConstraint
    {
        PxConstraintSolverPrep  prep;
        const void*             constantBlock;
    };

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

    PX_C_EXPORT PX_PHYSX_CORE_API 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);

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

    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, PxU32 nbPairs, PxContactRecorder& contactRecorder,
                                                            PxReal contactDistance, PxReal meshContactMargin, PxReal toleranceLength, PxCacheAllocator& allocator);

    PX_C_EXPORT PX_PHYSX_CORE_API void PxRegisterImmediateArticulations();

    struct PxArticulationJointDataRC
    {
        PxTransform                     parentPose;
        PxTransform                     childPose;
        PxArticulationMotion::Enum      motion[PxArticulationAxis::eCOUNT];
        PxArticulationLimit             limits[PxArticulationAxis::eCOUNT];
        PxArticulationDrive             drives[PxArticulationAxis::eCOUNT];
        PxReal                          targetPos[PxArticulationAxis::eCOUNT];
        PxReal                          targetVel[PxArticulationAxis::eCOUNT];
        PxReal                          armature[PxArticulationAxis::eCOUNT];
        PxReal                          jointPos[PxArticulationAxis::eCOUNT];
        PxReal                          jointVel[PxArticulationAxis::eCOUNT];
        PxReal                          frictionCoefficient;
        PxReal                          maxJointVelocity;
        PxArticulationJointType::Enum   type;

        void    initData()
        {
            parentPose          = PxTransform(PxIdentity);
            childPose           = PxTransform(PxIdentity);
            frictionCoefficient = 0.05f;
            maxJointVelocity    = 100.0f;
            type                = PxArticulationJointType::eUNDEFINED;  // For root

            for(PxU32 i=0;i<PxArticulationAxis::eCOUNT;i++)
            {
                motion[i] = PxArticulationMotion::eLOCKED;
                limits[i] = PxArticulationLimit(0.0f, 0.0f);
                drives[i] = PxArticulationDrive(0.0f, 0.0f, 0.0f);
                armature[i] = 0.0f;
                jointPos[i] = 0.0f;
                jointVel[i] = 0.0f;
            }
            PxMemSet(targetPos, 0xff, sizeof(PxReal)*PxArticulationAxis::eCOUNT);
            PxMemSet(targetVel, 0xff, sizeof(PxReal)*PxArticulationAxis::eCOUNT);
        }
    };

    struct PxArticulationDataRC
    {
        PxArticulationFlags     flags;
    };

    struct PxArticulationLinkMutableDataRC
    {
        PxVec3  inverseInertia;
        float   inverseMass;
        float   linearDamping;
        float   angularDamping;
        float   maxLinearVelocitySq;
        float   maxAngularVelocitySq;
        float   cfmScale;
        bool    disableGravity;

        void    initData()
        {
            inverseInertia          = PxVec3(1.0f);
            inverseMass             = 1.0f;
            linearDamping           = 0.05f;
            angularDamping          = 0.05f;
            maxLinearVelocitySq     = 100.0f * 100.0f;
            maxAngularVelocitySq    = 50.0f * 50.0f;
            cfmScale                = 0.025f;
            disableGravity          = false;
        }
    };

    struct PxArticulationLinkDerivedDataRC
    {
        PxTransform pose;
        PxVec3      linearVelocity;
        PxVec3      angularVelocity;
    };

    struct PxArticulationLinkDataRC : PxArticulationLinkMutableDataRC
    {
        PxArticulationLinkDataRC()  { PxArticulationLinkDataRC::initData(); }

        void    initData()
        {
            pose = PxTransform(PxIdentity);

            PxArticulationLinkMutableDataRC::initData();
            inboundJoint.initData();
        }

        PxArticulationJointDataRC   inboundJoint;
        PxTransform                 pose;
    };

    typedef void* PxArticulationCookie;

    struct PxArticulationLinkCookie
    {
        PxArticulationCookie    articulation;
        PxU32                   linkId;
    };

    struct PxCreateArticulationLinkCookie : PxArticulationLinkCookie
    {
        PX_FORCE_INLINE PxCreateArticulationLinkCookie(PxArticulationCookie art=NULL, PxU32 id=0xffffffff)
        {
            articulation    = art;
            linkId          = id;
        }
    };

    struct PxArticulationLinkHandle
    {
        PX_FORCE_INLINE         PxArticulationLinkHandle(PxArticulationHandle art=NULL, const PxU32 id=0xffffffff) : articulation(art), linkId(id) {}

        PxArticulationHandle    articulation;
        PxU32                   linkId;
    };

    PX_C_EXPORT PX_PHYSX_CORE_API PxArticulationCookie PxBeginCreateArticulationRC(const PxArticulationDataRC& data);

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

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

    PX_C_EXPORT PX_PHYSX_CORE_API void PxReleaseArticulation(PxArticulationHandle articulation);

    PX_C_EXPORT PX_PHYSX_CORE_API PxArticulationCache* PxCreateArticulationCache(PxArticulationHandle articulation);

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

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

    PX_C_EXPORT PX_PHYSX_CORE_API void PxReleaseArticulationCache(PxArticulationCache& cache);

    PX_C_EXPORT PX_PHYSX_CORE_API bool PxGetLinkData(const PxArticulationLinkHandle& link, PxArticulationLinkDerivedDataRC& data);

    PX_C_EXPORT PX_PHYSX_CORE_API PxU32 PxGetAllLinkData(const PxArticulationHandle articulation, PxArticulationLinkDerivedDataRC* data);

    PX_C_EXPORT PX_PHYSX_CORE_API bool PxGetMutableLinkData(const PxArticulationLinkHandle& link, PxArticulationLinkMutableDataRC& data);

    PX_C_EXPORT PX_PHYSX_CORE_API bool PxSetMutableLinkData(const PxArticulationLinkHandle& link, const PxArticulationLinkMutableDataRC& data);

    PX_C_EXPORT PX_PHYSX_CORE_API bool PxGetJointData(const PxArticulationLinkHandle& link, PxArticulationJointDataRC& data);

    PX_C_EXPORT PX_PHYSX_CORE_API bool PxSetJointData(const PxArticulationLinkHandle& link, const PxArticulationJointDataRC& data);

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

    PX_C_EXPORT PX_PHYSX_CORE_API void PxUpdateArticulationBodies(PxArticulationHandle articulation, const PxReal dt);

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

    PX_C_EXPORT PX_PHYSX_CORE_API void PxUpdateArticulationBodiesTGS(PxArticulationHandle articulation, const PxReal dt);

    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, const bool gyroscopicForces = false);

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

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

    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);

    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);

    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);

    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);

    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 = 0, PxArticulationHandle* solverArticulations = NULL, PxSpatialVector* Z = NULL, PxSpatialVector* deltaV = NULL);

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

    typedef PX_DEPRECATED PxArticulationJointDataRC         PxFeatherstoneArticulationJointData;
    typedef PX_DEPRECATED PxArticulationLinkDataRC          PxFeatherstoneArticulationLinkData;
    typedef PX_DEPRECATED PxArticulationDataRC              PxFeatherstoneArticulationData;
    typedef PX_DEPRECATED PxArticulationLinkMutableDataRC   PxMutableLinkData;
    typedef PX_DEPRECATED PxArticulationLinkDerivedDataRC   PxLinkData;

#if !PX_DOXYGEN
}
#endif

#if !PX_DOXYGEN
}
#endif

#endif