Upgrade to PhysX 5.1.3

This commit is contained in:
Wojtek Figat
2023-03-03 17:13:46 +01:00
parent 0112f70c05
commit a26d0d03eb
452 changed files with 58188 additions and 8646 deletions

View File

@@ -268,18 +268,28 @@ CollisionData::LoadResult CollisionData::load(const SerializedOptions* options,
if (dataSize <= 0)
return LoadResult::InvalidData;
// Create PhysX object
// Create physics object
if (_options.Type == CollisionDataType::ConvexMesh)
{
_convexMesh = PhysicsBackend::CreateConvexMesh(dataPtr, dataSize, _options.Box);
if (!_convexMesh)
{
LOG(Error, "Failed to create convex mesh");
return LoadResult::Failed;
}
}
else if (_options.Type == CollisionDataType::TriangleMesh)
{
_triangleMesh = PhysicsBackend::CreateTriangleMesh(dataPtr, dataSize, _options.Box);
if (!_triangleMesh)
{
LOG(Error, "Failed to create triangle mesh");
return LoadResult::Failed;
}
}
else
{
LOG(Warning, "Invalid collision data type.");
LOG(Error, "Invalid collision data type.");
return LoadResult::InvalidData;
}
}

View File

@@ -51,7 +51,7 @@
#define PHYSX_DEBUG_NAMING 0
// Temporary result buffer size
#define PHYSX_HIT_BUFFER_SIZE 128
#define PHYSX_HIT_BUFFER_SIZE 128
struct ActionDataPhysX
{
@@ -75,7 +75,8 @@ struct ScenePhysX
Array<ActionDataPhysX> Actions;
#if WITH_VEHICLE
Array<WheeledVehicle*> WheelVehicles;
PxBatchQuery* WheelRaycastBatchQuery = nullptr;
PxBatchQueryExt* WheelRaycastBatchQuery = nullptr;
int32 WheelRaycastBatchQuerySize = 0;
#endif
};
@@ -83,6 +84,7 @@ class AllocatorPhysX : public PxAllocatorCallback
{
void* allocate(size_t size, const char* typeName, const char* filename, int line) override
{
ASSERT(size < 1024 * 1024 * 32); // Prevent invalid allocation size
return Allocator::Allocate(size, 16);
}
@@ -124,7 +126,7 @@ class QueryFilterPhysX : public PxQueryFilterCallback
return blockSingle ? PxQueryHitType::eBLOCK : PxQueryHitType::eTOUCH;
}
PxQueryHitType::Enum postFilter(const PxFilterData& filterData, const PxQueryHit& hit) override
PxQueryHitType::Enum postFilter(const PxFilterData& filterData, const PxQueryHit& hit, const PxShape* shape, const PxRigidActor* actor) override
{
// Not used
return PxQueryHitType::eNONE;
@@ -151,7 +153,7 @@ class CharacterQueryFilterPhysX : public PxQueryFilterCallback
return PxQueryHitType::eNONE;
}
PxQueryHitType::Enum postFilter(const PxFilterData& filterData, const PxQueryHit& hit) override
PxQueryHitType::Enum postFilter(const PxFilterData& filterData, const PxQueryHit& hit, const PxShape* shape, const PxRigidActor* actor) override
{
// Not used
return PxQueryHitType::eNONE;
@@ -200,6 +202,35 @@ class CharacterControllerFilterPhysX : public PxControllerFilterCallback
}
};
#if WITH_VEHICLE
class WheelFilterPhysX : public PxQueryFilterCallback
{
public:
PxQueryHitType::Enum preFilter(const PxFilterData& filterData, const PxShape* shape, const PxRigidActor* actor, PxHitFlags& queryFlags) override
{
if (!shape)
return PxQueryHitType::eNONE;
const PxFilterData shapeFilter = shape->getQueryFilterData();
// Hardcoded id for vehicle shapes masking
if (filterData.word3 == shapeFilter.word3)
{
return PxQueryHitType::eNONE;
}
// Collide for pairs (A,B) where the filtermask of A contains the ID of B and vice versa
if ((filterData.word0 & shapeFilter.word1) && (shapeFilter.word0 & filterData.word1))
{
return PxQueryHitType::eBLOCK;
}
return PxQueryHitType::eNONE;
}
};
#endif
class WriteStreamPhysX : public PxOutputStream
{
public:
@@ -363,13 +394,12 @@ namespace
#if WITH_VEHICLE
bool VehicleSDKInitialized = false;
Array<PxVehicleWheels*> WheelVehiclesCache;
Array<PxRaycastQueryResult> WheelQueryResults;
Array<PxRaycastHit> WheelHitResults;
Array<PxWheelQueryResult> WheelVehiclesResultsPerWheel;
Array<PxVehicleWheelQueryResult> WheelVehiclesResultsPerVehicle;
PxVehicleDrivableSurfaceToTireFrictionPairs* WheelTireFrictions = nullptr;
bool WheelTireFrictionsDirty = false;
Array<float> WheelTireTypes;
WheelFilterPhysX WheelRaycastFilter;
#endif
}
@@ -482,23 +512,6 @@ void InitVehicleSDK()
}
}
PxQueryHitType::Enum WheelRaycastPreFilter(PxFilterData filterData0, PxFilterData filterData1, const void* constantBlock, PxU32 constantBlockSize, PxHitFlags& queryFlags)
{
// Hardcoded id for vehicle shapes masking
if (filterData0.word3 == filterData1.word3)
{
return PxQueryHitType::eNONE;
}
// Collide for pairs (A,B) where the filtermask of A contains the ID of B and vice versa
if ((filterData0.word0 & filterData1.word1) && (filterData1.word0 & filterData0.word1))
{
return PxQueryHitType::eBLOCK;
}
return PxQueryHitType::eNONE;
}
#endif
void* PhysicalMaterial::GetPhysicsMaterial()
@@ -757,8 +770,6 @@ void PhysicsBackend::Shutdown()
// Cleanup any resources
#if WITH_VEHICLE
RELEASE_PHYSX(WheelTireFrictions);
WheelQueryResults.Resize(0);
WheelHitResults.Resize(0);
WheelVehiclesResultsPerWheel.Resize(0);
WheelVehiclesResultsPerVehicle.Resize(0);
#endif
@@ -794,7 +805,6 @@ void PhysicsBackend::ApplySettings(const PhysicsSettings& settings)
_frictionCombineMode = settings.FrictionCombineMode;
_restitutionCombineMode = settings.RestitutionCombineMode;
// TODO: setting eADAPTIVE_FORCE requires PxScene setup (physx docs: This flag is not mutable, and must be set in PxSceneDesc at scene creation.)
// TODO: update all shapes filter data
// TODO: update all shapes flags
@@ -824,11 +834,10 @@ void* PhysicsBackend::CreateScene(const PhysicsSettings& settings)
sceneDesc.flags |= PxSceneFlag::eENABLE_ACTIVE_ACTORS;
if (!settings.DisableCCD)
sceneDesc.flags |= PxSceneFlag::eENABLE_CCD;
if (settings.EnableAdaptiveForce)
sceneDesc.flags |= PxSceneFlag::eADAPTIVE_FORCE;
sceneDesc.simulationEventCallback = &scenePhysX->EventsCallback;
sceneDesc.filterShader = FilterShader;
sceneDesc.bounceThresholdVelocity = settings.BounceThresholdVelocity;
sceneDesc.solverType = PxSolverType::ePGS;
if (sceneDesc.cpuDispatcher == nullptr)
{
scenePhysX->CpuDispatcher = PxDefaultCpuDispatcherCreate(Math::Clamp<uint32>(Platform::GetCPUInfo().ProcessorCoreCount - 1, 1, 4));
@@ -870,6 +879,7 @@ void PhysicsBackend::DestroyScene(void* scene)
SceneOrigins.Remove(scenePhysX->Scene);
#if WITH_VEHICLE
RELEASE_PHYSX(scenePhysX->WheelRaycastBatchQuery);
scenePhysX->WheelRaycastBatchQuerySize = 0;
#endif
RELEASE_PHYSX(scenePhysX->ControllerManager);
SAFE_DELETE(scenePhysX->CpuDispatcher);
@@ -1108,18 +1118,12 @@ void PhysicsBackend::EndSimulateScene(void* scene)
}
// Update batches queries cache
if (wheelsCount > WheelQueryResults.Count())
if (wheelsCount > scenePhysX->WheelRaycastBatchQuerySize)
{
if (scenePhysX->WheelRaycastBatchQuery)
scenePhysX->WheelRaycastBatchQuery->release();
WheelQueryResults.Resize(wheelsCount, false);
WheelHitResults.Resize(wheelsCount, false);
PxBatchQueryDesc desc(wheelsCount, 0, 0);
desc.queryMemory.userRaycastResultBuffer = WheelQueryResults.Get();
desc.queryMemory.userRaycastTouchBuffer = WheelHitResults.Get();
desc.queryMemory.raycastTouchBufferSize = wheelsCount;
desc.preFilterShader = WheelRaycastPreFilter;
scenePhysX->WheelRaycastBatchQuery = scenePhysX->Scene->createBatchQuery(desc);
scenePhysX->WheelRaycastBatchQuerySize = wheelsCount;
scenePhysX->WheelRaycastBatchQuery = PxCreateBatchQueryExt(*scenePhysX->Scene, &WheelRaycastFilter, wheelsCount, wheelsCount, 0, 0, 0, 0);
}
// Update lookup table that maps wheel type into the surface friction
@@ -1169,7 +1173,7 @@ void PhysicsBackend::EndSimulateScene(void* scene)
// Update vehicles
if (WheelVehiclesCache.Count() != 0)
{
PxVehicleSuspensionRaycasts(scenePhysX->WheelRaycastBatchQuery, WheelVehiclesCache.Count(), WheelVehiclesCache.Get(), WheelQueryResults.Count(), WheelQueryResults.Get());
PxVehicleSuspensionRaycasts(scenePhysX->WheelRaycastBatchQuery, WheelVehiclesCache.Count(), WheelVehiclesCache.Get());
PxVehicleUpdates(scenePhysX->LastDeltaTime, scenePhysX->Scene->getGravity(), *WheelTireFrictions, WheelVehiclesCache.Count(), WheelVehiclesCache.Get(), WheelVehiclesResultsPerVehicle.Get());
}
@@ -2045,7 +2049,7 @@ bool PhysicsBackend::ComputeShapesPenetration(void* shapeA, void* shapeB, const
const PxTransform poseA(C2P(positionA), C2P(orientationA));
const PxTransform poseB(C2P(positionB), C2P(orientationB));
PxVec3 dir = C2P(direction);
const bool result = PxGeometryQuery::computePenetration(dir, distance, shapeAPhysX->getGeometry().any(), poseA, shapeBPhysX->getGeometry().any(), poseB);
const bool result = PxGeometryQuery::computePenetration(dir, distance, shapeAPhysX->getGeometry(), poseA, shapeBPhysX->getGeometry(), poseB);
direction = P2C(dir);
return result;
}
@@ -2054,7 +2058,7 @@ float PhysicsBackend::ComputeShapeSqrDistanceToPoint(void* shape, const Vector3&
{
auto shapePhysX = (PxShape*)shape;
const PxTransform trans(C2P(position), C2P(orientation));
return PxGeometryQuery::pointDistance(C2P(point), shapePhysX->getGeometry().any(), trans, (PxVec3*)closestPoint);
return PxGeometryQuery::pointDistance(C2P(point), shapePhysX->getGeometry(), trans, (PxVec3*)closestPoint);
}
bool PhysicsBackend::RayCastShape(void* shape, const Vector3& position, const Quaternion& orientation, const Vector3& origin, const Vector3& direction, float& resultHitDistance, float maxDistance)
@@ -2064,7 +2068,7 @@ bool PhysicsBackend::RayCastShape(void* shape, const Vector3& position, const Qu
const PxTransform trans(C2P(position - sceneOrigin), C2P(orientation));
const PxHitFlags hitFlags = (PxHitFlags)0;
PxRaycastHit hit;
if (PxGeometryQuery::raycast(C2P(origin - sceneOrigin), C2P(direction), shapePhysX->getGeometry().any(), trans, maxDistance, hitFlags, 1, &hit) != 0)
if (PxGeometryQuery::raycast(C2P(origin - sceneOrigin), C2P(direction), shapePhysX->getGeometry(), trans, maxDistance, hitFlags, 1, &hit) != 0)
{
resultHitDistance = hit.distance;
return true;
@@ -2079,7 +2083,7 @@ bool PhysicsBackend::RayCastShape(void* shape, const Vector3& position, const Qu
const PxTransform trans(C2P(position - sceneOrigin), C2P(orientation));
const PxHitFlags hitFlags = PxHitFlag::ePOSITION | PxHitFlag::eNORMAL | PxHitFlag::eFACE_INDEX | PxHitFlag::eUV;
PxRaycastHit hit;
if (PxGeometryQuery::raycast(C2P(origin - sceneOrigin), C2P(direction), shapePhysX->getGeometry().any(), trans, maxDistance, hitFlags, 1, &hit) == 0)
if (PxGeometryQuery::raycast(C2P(origin - sceneOrigin), C2P(direction), shapePhysX->getGeometry(), trans, maxDistance, hitFlags, 1, &hit) == 0)
return false;
P2C(hit, hitInfo);
hitInfo.Point += sceneOrigin;
@@ -2905,7 +2909,8 @@ void* PhysicsBackend::CreateConvexMesh(byte* data, int32 dataSize, BoundingBox&
{
PxDefaultMemoryInputData input(data, dataSize);
PxConvexMesh* convexMesh = PhysX->createConvexMesh(input);
localBounds = P2C(convexMesh->getLocalBounds());
if (convexMesh)
localBounds = P2C(convexMesh->getLocalBounds());
return convexMesh;
}
@@ -2913,7 +2918,8 @@ void* PhysicsBackend::CreateTriangleMesh(byte* data, int32 dataSize, BoundingBox
{
PxDefaultMemoryInputData input(data, dataSize);
PxTriangleMesh* triangleMesh = PhysX->createTriangleMesh(input);
localBounds = P2C(triangleMesh->getLocalBounds());
if (triangleMesh)
localBounds = P2C(triangleMesh->getLocalBounds());
return triangleMesh;
}

View File

@@ -32,7 +32,7 @@ bool MultiThreadStepper::advance(PxScene* scene, PxReal dt, void* scratchBlock,
mScratchBlockSize = scratchBlockSize;
if (!mSync)
mSync = New<shdfnd::Sync>();
mSync = New<PxSync>();
substepStrategy(dt, mNbSubSteps, mSubStepSize);

View File

@@ -7,7 +7,7 @@
#include "Types.h"
#include <ThirdParty/PhysX/task/PxTask.h>
#include <ThirdParty/PhysX/foundation/PxSimpleTypes.h>
#include <ThirdParty/PhysX/foundation/PsSync.h>
#include <ThirdParty/PhysX/foundation/PxSync.h>
class MultiThreadStepper;
@@ -135,7 +135,7 @@ protected:
StepperTaskSimulate mSimulateTask;
StepperTask mCompletion0, mCompletion1;
PxScene* mScene;
shdfnd::Sync* mSync;
PxSync* mSync;
PxU32 mCurrentSubStep;
PxU32 mNbSubSteps;

View File

@@ -21,16 +21,44 @@
namespace physx
{
template<class Type>
class PxVec2T;
typedef PxVec2T<float> PxVec2;
template<class Type>
class PxVec3T;
typedef PxVec3T<float> PxVec3;
template<class Type>
class PxVec4T;
typedef PxVec4T<float> PxVec4;
template<class Type>
class PxQuatT;
typedef PxQuatT<float> PxQuat;
template<class Type>
class PxMat33T;
typedef PxMat33T<float> PxMat33;
template<class Type>
class PxMat34T;
typedef PxMat34T<float> PxMat34;
template<class Type>
class PxMat44T;
typedef PxMat44T<float> PxMat44;
template<class Type>
class PxTransformT;
typedef PxTransformT<float> PxTransform;
class PxScene;
class PxConvexMesh;
class PxTriangleMesh;
class PxCooking;
class PxPhysics;
class PxVec3;
class PxVec4;
class PxTransform;
class PxJoint;
class PxMat44;
class PxCpuDispatcher;
class PxGpuDispatcher;
class PxSimulationEventCallback;
@@ -55,6 +83,8 @@ namespace physx
class PxQueryFilterCallback;
class PxControllerFilterCallback;
class PxHeightField;
class PxPlane;
class PxBounds3;
struct PxFilterData;
struct PxRaycastHit;
struct PxSweepHit;

View File

@@ -56,7 +56,6 @@ void PhysicsSettings::Deserialize(DeserializeStream& stream, ISerializeModifier*
DESERIALIZE(FrictionCombineMode);
DESERIALIZE(RestitutionCombineMode);
DESERIALIZE(DisableCCD);
DESERIALIZE(EnableAdaptiveForce);
DESERIALIZE(MaxDeltaTime);
DESERIALIZE(EnableSubstepping);
DESERIALIZE(SubstepDeltaTime);

View File

@@ -43,12 +43,6 @@ public:
API_FIELD(Attributes="EditorOrder(70), EditorDisplay(\"Simulation\")")
bool DisableCCD = false;
/// <summary>
/// Enables adaptive forces to accelerate convergence of the solver. Can improve physics simulation performance but lead to artifacts.
/// </summary>
API_FIELD(Attributes="EditorOrder(80), EditorDisplay(\"Simulation\")")
bool EnableAdaptiveForce = false;
/// <summary>
/// The maximum allowed delta time (in seconds) for the physics simulation step.
/// </summary>

View File

@@ -892,7 +892,7 @@ bool TerrainPatch::SetupHeightMap(int32 heightMapLength, const float* heightMap,
collisionData = &tmpData;
}
// Generate PhysX height field data for the runtime
// Generate physics backend height field data for the runtime
if (CookCollision(info, initData, _terrain->_collisionLod, collisionData))
{
return true;
@@ -1853,7 +1853,7 @@ void TerrainPatch::SaveHeightData()
return;
}
// Generate PhysX height field data for the runtime
// Generate physics backend height field data for the runtime
if (_heightfield->WaitForLoaded())
{
LOG(Error, "Failed to load patch heightfield data.");

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

BIN
Source/Platforms/Android/Binaries/ThirdParty/ARM64/libPhysX_static_64.a (Stored with Git LFS) vendored Normal file

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@@ -1,9 +1,31 @@
Copyright (c) 2018 NVIDIA Corporation. All rights reserved. Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
BSD 3-Clause License
Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
Copyright (c) 2023, NVIDIA Corporation
All rights reserved.
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.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:
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.
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
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.
* 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.

View File

@@ -6,7 +6,7 @@ using Flax.Build;
using Flax.Build.NativeCpp;
/// <summary>
/// https://github.com/NVIDIAGameWorks/PhysX
/// https://github.com/NVIDIA-Omniverse/PhysX
/// </summary>
public class PhysX : DepsModule
{
@@ -27,7 +27,7 @@ public class PhysX : DepsModule
{
base.Setup(options);
// PhysX 4 configuration:
// PhysX configuration:
// PX_BUILDSNIPPETS = False
// PX_BUILDSAMPLES = False
// PX_BUILDPUBLICSAMPLES = False
@@ -59,14 +59,18 @@ public class PhysX : DepsModule
case TargetPlatform.XboxOne:
case TargetPlatform.XboxScarlett:
case TargetPlatform.Mac:
case TargetPlatform.Android:
switch (options.Architecture)
{
case TargetArchitecture.x86:
case TargetArchitecture.ARM:
archPostFix = "_32";
break;
case TargetArchitecture.x64:
case TargetArchitecture.ARM64:
archPostFix = "_64";
break;
default: throw new InvalidArchitectureException(options.Architecture);
}
break;
}

View File

@@ -1,4 +1,3 @@
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
@@ -11,7 +10,7 @@
// 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
// 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
@@ -23,13 +22,12 @@
// (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-2019 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2008-2023 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_PHYSICS_NX_ACTOR
#define PX_PHYSICS_NX_ACTOR
#ifndef PX_ACTOR_H
#define PX_ACTOR_H
/** \addtogroup physics
@{
@@ -49,11 +47,12 @@ class PxRigidActor;
class PxRigidBody;
class PxRigidStatic;
class PxRigidDynamic;
class PxArticulation;
class PxArticulationLink;
class PxScene;
/** Group index which allows to specify 1- or 2-way interaction */
/**
\brief Group index which allows to specify 1- or 2-way interaction
*/
typedef PxU8 PxDominanceGroup; // Must be < 32, PxU8.
/**
@@ -93,7 +92,7 @@ struct PxActorFlag
\note Setting this flag will remove all constraints attached to the actor from the scene.
\note If this flag is set, the following calls are forbidden:
\li PxRigidBody: setLinearVelocity(), setAngularVelocity(), addForce(), addTorque(), clearForce(), clearTorque()
\li PxRigidBody: setLinearVelocity(), setAngularVelocity(), addForce(), addTorque(), clearForce(), clearTorque(), setForceAndTorque()
\li PxRigidDynamic: setKinematicTarget(), setWakeCounter(), wakeUp(), putToSleep()
\par <b>Sleeping:</b>
@@ -138,9 +137,57 @@ struct PxActorType
*/
eARTICULATION_LINK,
//brief internal use only!
/**
\brief A FEM-based soft body
@see PxSoftBody
*/
eSOFTBODY,
/**
\brief A FEM-based cloth
\note In development
@see PxFEMCloth
*/
eFEMCLOTH,
/**
\brief A PBD ParticleSystem
@see PxPBDParticleSystem
*/
ePBD_PARTICLESYSTEM,
/**
\brief A FLIP ParticleSystem
\note In development
@see PxFLIPParticleSystem
*/
eFLIP_PARTICLESYSTEM,
/**
\brief A MPM ParticleSystem
\note In development
@see PxMPMParticleSystem
*/
eMPM_PARTICLESYSTEM,
/**
\brief A CUSTOM ParticleSystem
\note In development
@see PxCUSTOMParticleSystem
*/
eCUSTOM_PARTICLESYSTEM,
/**
\brief A HairSystem
\note In development
@see PxHairSystem
*/
eHAIRSYSTEM,
//! \brief internal use only!
eACTOR_COUNT,
//! \brief internal use only!
eACTOR_FORCE_DWORD = 0x7fffffff
};
};
@@ -149,7 +196,6 @@ struct PxActorType
\brief PxActor is the base class for the main simulation objects in the physics SDK.
The actor is owned by and contained in a PxScene.
*/
class PxActor : public PxBase
{
@@ -211,6 +257,9 @@ public:
/**
\brief Retrieves the axis aligned bounding box enclosing the actor.
\note It is not allowed to use this method while the simulation is running (except during PxScene::collide(),
in PxContactModifyCallback or in contact report callbacks).
\param[in] inflation Scale factor for computed world bounds. Box extents are multiplied by this value.
\return The actor's bounding box.
@@ -229,13 +278,12 @@ public:
\param[in] flag The PxActor flag to raise(set) or clear. See #PxActorFlag.
\param[in] value The boolean value to assign to the flag.
<b>Default:</b> PxActorFlag::eVISUALIZATION
@see PxActorFlag getActorFlags()
*/
virtual void setActorFlag(PxActorFlag::Enum flag, bool value) = 0;
/**
\brief sets the actor flags
\brief Sets the actor flags.
See the list of flags #PxActorFlag
@see PxActorFlag setActorFlag()
@@ -293,7 +341,7 @@ public:
virtual void setOwnerClient( PxClientID inClient ) = 0;
/**
\brief Returns the owner client that was specified with at creation time.
\brief Returns the owner client that was specified at creation time.
This value cannot be changed once the object is placed into the scene.

111
Source/ThirdParty/PhysX/PxActorData.h vendored Normal file
View File

@@ -0,0 +1,111 @@
// 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-2023 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_ACTOR_DATA_H
#define PX_ACTOR_DATA_H
/** \addtogroup physics
@{
*/
#include "foundation/PxVec4.h"
#include "foundation/PxQuat.h"
#include "foundation/PxFlags.h"
#include "PxNodeIndex.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Identifies each type of information for retrieving from actor.
@see PxScene::applyActorData
*/
struct PxActorCacheFlag
{
enum Enum
{
eACTOR_DATA = (1 << 0), //include transform and velocity
eFORCE = (1 << 2),
eTORQUE = (1 << 3)
};
};
/**
\brief Collection of set bits defined in PxActorCacheFlag.
@see PxActorCacheFlag
*/
typedef PxFlags<PxActorCacheFlag::Enum, PxU16> PxActorCacheFlags;
PX_FLAGS_OPERATORS(PxActorCacheFlag::Enum, PxU16)
/**
\brief State of a body used when interfacing with the GPU rigid body pipeline
@see PxScene.copyBodyData()
*/
PX_ALIGN_PREFIX(16)
struct PxGpuBodyData
{
PxQuat quat; /*!< actor global pose quaternion in world frame */
PxVec4 pos; /*!< (x,y,z members): actor global pose position in world frame */
PxVec4 linVel; /*!< (x,y,z members): linear velocity at center of gravity in world frame */
PxVec4 angVel; /*!< (x,y,z members): angular velocity in world frame */
}
PX_ALIGN_SUFFIX(16);
/**
\brief Pair correspondence used for matching array indices with body node indices
*/
PX_ALIGN_PREFIX(8)
struct PxGpuActorPair
{
PxU32 srcIndex; //Defines which index in src array we read
PxNodeIndex nodeIndex; //Defines which actor this entry in src array is updating
}
PX_ALIGN_SUFFIX(8);
/**
\brief Maps numeric index to a data pointer.
@see PxScene::computeDenseJacobians(), PxScene::computeGeneralizedMassMatrices(), PxScene::computeGeneralizedGravityForces(), PxScene::computeCoriolisAndCentrifugalForces()
*/
struct PxIndexDataPair
{
PxU32 index;
void* data;
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@@ -1,4 +1,3 @@
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
@@ -11,7 +10,7 @@
// 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
// 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
@@ -23,13 +22,12 @@
// (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-2019 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2008-2023 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_PHYSICS_NX_AGGREGATE
#define PX_PHYSICS_NX_AGGREGATE
#ifndef PX_AGGREGATE_H
#define PX_AGGREGATE_H
/** \addtogroup physics
@{
@@ -38,14 +36,44 @@
#include "PxPhysXConfig.h"
#include "common/PxBase.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxActor;
class PxBVHStructure;
class PxBVH;
class PxScene;
struct PxAggregateType
{
enum Enum
{
eGENERIC = 0, //!< Aggregate will contain various actors of unspecified types
eSTATIC = 1, //!< Aggregate will only contain static actors
eKINEMATIC = 2 //!< Aggregate will only contain kinematic actors
};
};
// PxAggregateFilterHint is used for more efficient filtering of aggregates outside of the broadphase.
// It is a combination of a PxAggregateType and a self-collision bit.
typedef PxU32 PxAggregateFilterHint;
PX_CUDA_CALLABLE PX_FORCE_INLINE PxAggregateFilterHint PxGetAggregateFilterHint(PxAggregateType::Enum type, bool enableSelfCollision)
{
const PxU32 selfCollisionBit = enableSelfCollision ? 1 : 0;
return PxAggregateFilterHint((PxU32(type)<<1)|selfCollisionBit);
}
PX_CUDA_CALLABLE PX_FORCE_INLINE PxU32 PxGetAggregateSelfCollisionBit(PxAggregateFilterHint hint)
{
return hint & 1;
}
PX_CUDA_CALLABLE PX_FORCE_INLINE PxAggregateType::Enum PxGetAggregateType(PxAggregateFilterHint hint)
{
return PxAggregateType::Enum(hint>>1);
}
/**
\brief Class to aggregate actors into a single broad-phase entry.
@@ -66,7 +94,6 @@ large number of attached shapes).
@see PxActor, PxPhysics.createAggregate
*/
class PxAggregate : public PxBase
{
public:
@@ -79,7 +106,7 @@ public:
to delete both the PxAggregate and its actors, it is best to release the actors first, then release
the PxAggregate when it is empty.
*/
virtual void release() = 0;
virtual void release() = 0;
/**
\brief Adds an actor to the aggregate object.
@@ -92,17 +119,16 @@ public:
If the actor already belongs to a scene, a warning is output and the call is ignored. You need to remove
the actor from the scene first, before adding it to the aggregate.
\note When BVHStructure is provided the actor shapes are grouped together.
\note When a BVH is provided the actor shapes are grouped together.
The scene query pruning structure inside PhysX SDK will store/update one
bound per actor. The scene queries against such an actor will query actor
bounds and then make a local space query against the provided BVH structure, which is in
actor's local space.
bounds and then make a local space query against the provided BVH, which is in actor's local space.
\param [in] actor The actor that should be added to the aggregate
\param [in] bvhStructure BVHStructure for actor shapes.
\param [in] actor The actor that should be added to the aggregate
\param [in] bvh BVH for actor shapes.
return true if success
*/
virtual bool addActor(PxActor& actor, const PxBVHStructure* bvhStructure = NULL) = 0;
virtual bool addActor(PxActor& actor, const PxBVH* bvh = NULL) = 0;
/**
\brief Removes an actor from the aggregate object.
@@ -115,7 +141,7 @@ public:
\param [in] actor The actor that should be removed from the aggregate
return true if success
*/
virtual bool removeActor(PxActor& actor) = 0;
virtual bool removeActor(PxActor& actor) = 0;
/**
\brief Adds an articulation to the aggregate object.
@@ -131,20 +157,20 @@ public:
\param [in] articulation The articulation that should be added to the aggregate
return true if success
*/
virtual bool addArticulation(PxArticulationBase& articulation) = 0;
virtual bool addArticulation(PxArticulationReducedCoordinate& articulation) = 0;
/**
\brief Removes an articulation from the aggregate object.
A warning is output if the incoming articulation does not belong to the aggregate. Otherwise the articulation is
removed from the aggregate. If the aggregate belongs to a scene, the articulation is reinserted in that
scene. If you intend to delete the articulation, it is best to call #PxArticulation::release() directly. That way
scene. If you intend to delete the articulation, it is best to call #PxArticulationReducedCoordinate::release() directly. That way
the articulation will be automatically removed from its aggregate (if any) and not reinserted in a scene.
\param [in] articulation The articulation that should be removed from the aggregate
return true if success
*/
virtual bool removeArticulation(PxArticulationBase& articulation) = 0;
virtual bool removeArticulation(PxArticulationReducedCoordinate& articulation) = 0;
/**
\brief Returns the number of actors contained in the aggregate.
@@ -155,16 +181,29 @@ public:
@see PxActor getActors()
*/
virtual PxU32 getNbActors() const = 0;
virtual PxU32 getNbActors() const = 0;
/**
\brief Retrieves max amount of actors that can be contained in the aggregate.
\return Max aggregate size.
\note PxAggregate now supports an arbitrary number of actors. This method return PX_MAX_U32 and will be
removed in a future release.
\return Max actor size.
@see PxPhysics::createAggregate()
@deprecated
*/
PX_DEPRECATED virtual PxU32 getMaxNbActors() const = 0;
/**
\brief Retrieves max amount of shapes that can be contained in the aggregate.
\return Max shape size.
@see PxPhysics::createAggregate()
*/
virtual PxU32 getMaxNbActors() const = 0;
virtual PxU32 getMaxNbShapes() const = 0;
/**
\brief Retrieve all actors contained in the aggregate.
@@ -178,7 +217,7 @@ public:
@see PxShape getNbShapes()
*/
virtual PxU32 getActors(PxActor** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
virtual PxU32 getActors(PxActor** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
/**
\brief Retrieves the scene which this aggregate belongs to.
@@ -198,8 +237,10 @@ public:
virtual const char* getConcreteTypeName() const { return "PxAggregate"; }
void* userData; //!< user can assign this to whatever, usually to create a 1:1 relationship with a user object.
protected:
PX_INLINE PxAggregate(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags) {}
PX_INLINE PxAggregate(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags), userData(NULL) {}
PX_INLINE PxAggregate(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
virtual ~PxAggregate() {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxAggregate", name) || PxBase::isKindOf(name); }

View File

@@ -1,281 +0,0 @@
//
// 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-2019 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_PHYSICS_NX_ARTICULATION
#define PX_PHYSICS_NX_ARTICULATION
/** \addtogroup physics
@{ */
#include "PxArticulationBase.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxArticulationLink;
/**
\brief Articulation drive cache
This cache is used for making one or more impulse applications to the articulation.
@see PxArticulation PxArticulation.createDriveCache
*/
class PxArticulationDriveCache
{
protected:
PxArticulationDriveCache();
};
/**
\brief a tree structure of bodies connected by joints that is treated as a unit by the dynamics solver
Articulations are more expensive to simulate than the equivalent collection of
PxRigidDynamic and PxJoint structures, but because the dynamics solver treats
each articulation as a single object, they are much less prone to separation and
have better support for actuation. An articulation may have at most 64 links.
@see PxArticulationJoint PxArticulationLink PxPhysics.createArticulation
*/
#if PX_VC
#pragma warning(push)
#pragma warning(disable : 4435)
#endif
class PxArticulation : public PxArticulationBase
{
public:
virtual void release() = 0;
/**
\brief sets maxProjectionIterations.
This is the maximum number of iterations to run projection on the articulation to bring
the links back together if the separation tolerance is exceeded.
\param[in] iterations the maximum number of projection iterations
<b>Default:</b> 4
@see getMaxProjectionIterations()
*/
virtual void setMaxProjectionIterations(PxU32 iterations) = 0;
/**
\brief gets maxProjectionIterations.
\return the maximum number of projection iterations
@see setMaxProjectionIterations()
*/
virtual PxU32 getMaxProjectionIterations() const = 0;
/**
\brief sets separationTolerance.
This is the maximum allowed separation of any joint in the articulation before projection is used
<b>Default: 0.1f, scaled by the tolerance scale </b>
\param[in] tolerance the separation tolerance for the articulation
@see getSeparationTolerance()
*/
virtual void setSeparationTolerance(PxReal tolerance) = 0;
/**
\brief gets separationTolerance.
\return the separation tolerance
@see setSeparationTolerance()
*/
virtual PxReal getSeparationTolerance() const = 0;
/**
\brief sets the number of iterations used to compute the drive response to internal forces
The drive model uses an iterative algorithm to determine the load on each joint of the articulation.
This is the number of iterations to use when computing response of the drive to internal forces.
\param[in] iterations the number of iterations used to compute the drive response to internal forces.
<b>Default:</b> 4
@see getInternalDriveIterations()
*/
virtual void setInternalDriveIterations(PxU32 iterations) = 0;
/**
\brief gets internal driveIterations.
\return the number of iterations used to compute the drive response to internal forces
@see setInternalDriveIterations()
*/
virtual PxU32 getInternalDriveIterations() const = 0;
/**
\brief sets the number of iterations for drive response to external forces.
The drive model uses an iterative algorithm to determine the load on each joint of the articulation.
This is the number of iterations to use when computing response of the drive to external forces.
\param[in] iterations the number of iterations used to compute the drive response to external forces.
<b>Default:</b> 4
@see getExternalDriveIterations()
*/
virtual void setExternalDriveIterations(PxU32 iterations) = 0;
/**
\brief gets externalDriveIterations.
\return the number of iterations used to compute the drive response to external forces
@see setExternalDriveIterations()
*/
virtual PxU32 getExternalDriveIterations() const = 0;
/**
\brief create a drive cache for applying impulses which are propagated to the entire articulation
\param[in] compliance the compliance value to use at all joints of the articulation. This is equivalent to the external compliance
parameter for articulation joints, as the impulse is treated as an external force
\param[in] driveIterations the number of iterations to use to evaluate the drive strengths
\return a drive cache
@see PxArticulationDriveCache updateDriveCache releaseDriveCache applyImpulse computeImpulseResponse
\note this call may only be made on articulations that are in a scene, and may not be made during simulation
*/
virtual PxArticulationDriveCache*
createDriveCache(PxReal compliance, PxU32 driveIterations) const = 0;
/**
\brief update a drive cache
\param[in] driveCache the drive cache to update
\param[in] compliance the compliance value to use at all joints of the articulation.
\param[in] driveIterations the number of iterations to use to evaluate the drive strengths
@see releaseDriveCache createDriveCache applyImpulse computeImpulseResponse
\note this call may only be made on articulations that are in a scene, and may not be made during simulation
*/
virtual void updateDriveCache(PxArticulationDriveCache& driveCache,
PxReal compliance,
PxU32 driveIterations) const = 0;
/**
\brief release a drive cache
\param[in] driveCache the drive cache to release
@see createDriveCache updateDriveCache
*/
virtual void releaseDriveCache(PxArticulationDriveCache& driveCache) const = 0;
/**
\brief apply an impulse to an entire articulation
\param[in] link the link to which to apply the impulse
\param[in] driveCache the drive cache
\param[in] linearImpulse the linear impulse to apply
\param[in] angularImpulse the angular impulse to apply
@see computeImpulseResponse
\note this call may only be made on articulations that are in a scene, and may not be made during simulation
*/
virtual void applyImpulse(PxArticulationLink* link,
const PxArticulationDriveCache& driveCache,
const PxVec3& linearImpulse,
const PxVec3& angularImpulse) = 0;
/**
\brief determine the effect of applying an impulse to an entire articulation, without applying the impulse
\param[in] link the link to which to apply the impulse
\param[out] linearResponse the change in linear velocity of the articulation link
\param[out] angularResponse the change in angular velocity of the articulation link
\param[in] driveCache the drive cache
\param[in] linearImpulse the linear impulse to apply
\param[in] angularImpulse the angular impulse to apply
@see applyImpulse
This call will wake up the articulation if it is asleep.
\note this call may only be made on articulations that are in a scene, and may not be made during simulation
*/
virtual void computeImpulseResponse(PxArticulationLink*link,
PxVec3& linearResponse,
PxVec3& angularResponse,
const PxArticulationDriveCache& driveCache,
const PxVec3& linearImpulse,
const PxVec3& angularImpulse) const = 0;
protected:
PX_INLINE PxArticulation(PxType concreteType, PxBaseFlags baseFlags) : PxArticulationBase(concreteType, baseFlags){}
PX_INLINE PxArticulation(PxBaseFlags baseFlags) : PxArticulationBase(baseFlags){}
virtual ~PxArticulation() {}
};
#if PX_VC
#pragma warning(pop)
#endif
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@@ -1,320 +0,0 @@
//
// 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-2019 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_PHYSICS_NX_ARTICULATION_BASE
#define PX_PHYSICS_NX_ARTICULATION_BASE
/** \addtogroup physics
@{ */
#include "PxPhysXConfig.h"
#include "common/PxBase.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxArticulationImpl;
/**
\brief a tree structure of bodies connected by joints that is treated as a unit by the dynamics solver
Articulations are more expensive to simulate than the equivalent collection of
PxRigidDynamic and PxJoint structures, but because the dynamics solver treats
each articulation as a single object, they are much less prone to separation and
have better support for actuation. An articulation may have at most 64 links.
@see PxArticulationJoint PxArticulationLink PxPhysics.createArticulation
*/
class PxArticulationBase : public PxBase
{
public:
/**
\brief Retrieves the scene which this articulation belongs to.
\return Owner Scene. NULL if not part of a scene.
@see PxScene
*/
virtual PxScene* getScene() const = 0;
/**
\brief Sets the solver iteration counts for the articulation.
The solver iteration count determines how accurately joints and contacts are resolved.
If you are having trouble with jointed bodies oscillating and behaving erratically, then
setting a higher position iteration count may improve their stability.
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.
\param[in] minPositionIters Number of position iterations the solver should perform for this articulation. <b>Range:</b> [1,255]
\param[in] minVelocityIters Number of velocity iterations the solver should perform for this articulation. <b>Range:</b> [1,255]
@see getSolverIterationCounts()
*/
virtual void setSolverIterationCounts(PxU32 minPositionIters, PxU32 minVelocityIters = 1) = 0;
/**
\brief Retrieves the solver iteration counts.
@see setSolverIterationCounts()
*/
virtual void getSolverIterationCounts(PxU32 & minPositionIters, PxU32 & minVelocityIters) const = 0;
/**
\brief 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:
\li The wake counter is positive (see #setWakeCounter()).
\li The linear or angular velocity of any link is non-zero.
\li 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:
\li The wake counter is zero.
\li The linear and angular velocity of all links is zero.
\li 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 of dependent objects.
\note It is invalid to use this method if the articulation has not been added to a scene already.
\return True if the articulation is sleeping.
@see isSleeping() wakeUp() putToSleep() getSleepThreshold()
*/
virtual bool isSleeping() const = 0;
/**
\brief Sets the mass-normalized energy threshold below which an articulation may go to sleep.
The articulation will sleep if the energy of each body is below this threshold.
\param[in] threshold Energy below which an actor may go to sleep. <b>Range:</b> [0, PX_MAX_F32)
@see isSleeping() getSleepThreshold() wakeUp() putToSleep()
*/
virtual void setSleepThreshold(PxReal threshold) = 0;
/**
\brief Returns the mass-normalized energy below which an articulation may go to sleep.
\return The energy threshold for sleeping.
@see isSleeping() wakeUp() putToSleep() setSleepThreshold()
*/
virtual PxReal getSleepThreshold() const = 0;
/**
\brief Sets the mass-normalized kinetic energy threshold below which an articulation may participate in stabilization.
Articulation 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.
<b>Default:</b> 0.01 * PxTolerancesScale::speed * PxTolerancesScale::speed
\param[in] threshold Energy below which an actor may participate in stabilization. <b>Range:</b> [0,inf)
@see getStabilizationThreshold() PxSceneFlag::eENABLE_STABILIZATION
*/
virtual void setStabilizationThreshold(PxReal threshold) = 0;
/**
\brief Returns the mass-normalized kinetic energy below which an articulation may participate in stabilization.
Articulations whose kinetic energy divided by their mass is above this threshold will not participate in stabilization.
\return The energy threshold for participating in stabilization.
@see setStabilizationThreshold() PxSceneFlag::eENABLE_STABILIZATION
*/
virtual PxReal getStabilizationThreshold() const = 0;
/**
\brief Sets the wake counter for the articulation.
The wake counter value determines the minimum amount of time until the articulation can be put to sleep. Please note
that 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.
\note Passing in a positive value will wake the articulation up automatically.
<b>Default:</b> 0.4 (which corresponds to 20 frames for a time step of 0.02)
\param[in] wakeCounterValue Wake counter value. <b>Range:</b> [0, PX_MAX_F32)
@see isSleeping() getWakeCounter()
*/
virtual void setWakeCounter(PxReal wakeCounterValue) = 0;
/**
\brief Returns the wake counter of the articulation.
\return The wake counter of the articulation.
@see isSleeping() setWakeCounter()
*/
virtual PxReal getWakeCounter() const = 0;
/**
\brief 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.
\note This will set the wake counter of the articulation to the value specified in #PxSceneDesc::wakeCounterResetValue.
\note It is invalid to use this method if the articulation has not been added to a scene already.
@see isSleeping() putToSleep()
*/
virtual void wakeUp() = 0;
/**
\brief Forces the articulation to sleep.
The articulation will stay asleep during the next simulation step if not touched by another non-sleeping actor.
\note This will set any applied force, the velocity and the wake counter of all bodies in the articulation to zero.
\note It is invalid to use this method if the articulation has not been added to a scene already.
@see isSleeping() wakeUp()
*/
virtual void putToSleep() = 0;
/**
\brief adds a link to the articulation with default attribute values.
\param[in] parent the parent link of the articulation. Should be NULL if (and only if) this is the root link
\param[in] pose the initial pose of the new link. Must be a valid transform
\return the new link, or NULL if the link cannot be created because the articulation has reached
its maximum link count (currently 64).
@see PxArticulationLink
*/
virtual PxArticulationLink* createLink(PxArticulationLink* parent, const PxTransform& pose) = 0;
/**
\brief returns the number of links in the articulation
*/
virtual PxU32 getNbLinks() const = 0;
/**
\brief returns the set of links in the articulation
\param[in] userBuffer buffer into which to write an array of articulation link pointers
\param[in] bufferSize the size of the buffer. If this is not large enough to contain all the pointers to links,
only as many as will fit are written.
\param[in] startIndex Index of first link pointer to be retrieved
\return the number of links written into the buffer.
@see ArticulationLink
*/
virtual PxU32 getLinks(PxArticulationLink** userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0;
/**
\brief Sets a name string for the object 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.
\param[in] name String to set the objects name to.
@see getName()
*/
virtual void setName(const char* name) = 0;
/**
\brief Retrieves the name string set with setName().
\return Name string associated with object.
@see setName()
*/
virtual const char* getName() const = 0;
/**
\brief Retrieves the axis aligned bounding box enclosing the articulation.
\param[in] inflation Scale factor for computed world bounds. Box extents are multiplied by this value.
\return The articulation's bounding box.
@see PxBounds3
*/
virtual PxBounds3 getWorldBounds(float inflation = 1.01f) const = 0;
/**
\brief Retrieves the aggregate the articulation might be a part of.
\return The aggregate the articulation is a part of, or NULL if the articulation does not belong to an aggregate.
@see PxAggregate
*/
virtual PxAggregate* getAggregate() const = 0;
virtual PxArticulationImpl* getImpl() = 0;
virtual const PxArticulationImpl* getImpl() const = 0;
void* userData; //!< user can assign this to whatever, usually to create a 1:1 relationship with a user object.
virtual ~PxArticulationBase() {}
protected:
PX_INLINE PxArticulationBase(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags), userData(NULL) {}
PX_INLINE PxArticulationBase(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
public:
virtual PxArticulationJointBase* createArticulationJoint(PxArticulationLink& parent, const PxTransform& parentFrame, PxArticulationLink& child, const PxTransform& childFrame) = 0;
virtual void releaseArticulationJoint(PxArticulationJointBase* joint) = 0;
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@@ -0,0 +1,106 @@
// 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-2023 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_ARTICULATION_FLAG_H
#define PX_ARTICULATION_FLAG_H
#include "PxPhysXConfig.h"
#include "foundation/PxFlags.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief A description of the types of articulation data that may be directly written to and read from the GPU using the functions
PxScene::copyArticulationData() and PxScene::applyArticulationData(). Types that are read-only may only be used in conjunction with
PxScene::copyArticulationData(). Types that are write-only may only be used in conjunction with PxScene::applyArticulationData().
A subset of data types may be used in conjunction with both PxScene::applyArticulationData() and PxScene::applyArticulationData().
@see PxArticulationCache, PxScene::copyArticulationData(), PxScene::applyArticulationData()
*/
class PxArticulationGpuDataType
{
public:
enum Enum
{
eJOINT_POSITION = 0, //!< The joint positions, read and write, see PxScene::copyArticulationData(), PxScene::applyArticulationData()
eJOINT_VELOCITY, //!< The joint velocities, read and write, see PxScene::copyArticulationData(), PxScene::applyArticulationData()
eJOINT_ACCELERATION, //!< The joint accelerations, read only, see PxScene::copyArticulationData()
eJOINT_FORCE, //!< The applied joint forces, write only, see PxScene::applyArticulationData()
eJOINT_SOLVER_FORCE, //!< The computed joint constraint solver forces, read only, see PxScene::copyArticulationData()()
eJOINT_TARGET_VELOCITY, //!< The velocity targets for the joint drives, write only, see PxScene::applyArticulationData()
eJOINT_TARGET_POSITION, //!< The position targets for the joint drives, write only, see PxScene::applyArticulationData()
eSENSOR_FORCE, //!< The spatial sensor forces, read only, see PxScene::copyArticulationData()
eROOT_TRANSFORM, //!< The root link transform, read and write, see PxScene::copyArticulationData(), PxScene::applyArticulationData()
eROOT_VELOCITY, //!< The root link velocity, read and write, see PxScene::copyArticulationData(), PxScene::applyArticulationData()
eLINK_TRANSFORM, //!< The link transforms including root link, read only, see PxScene::copyArticulationData()
eLINK_VELOCITY, //!< The link velocities including root link, read only, see PxScene::copyArticulationData()
eLINK_FORCE, //!< The forces to apply to links, write only, see PxScene::applyArticulationData()
eLINK_TORQUE, //!< The torques to apply to links, write only, see PxScene::applyArticulationData()
eFIXED_TENDON, //!< Fixed tendon data, write only, see PxScene::applyArticulationData()
eFIXED_TENDON_JOINT, //!< Fixed tendon joint data, write only, see PxScene::applyArticulationData()
eSPATIAL_TENDON, //!< Spatial tendon data, write only, see PxScene::applyArticulationData()
eSPATIAL_TENDON_ATTACHMENT //!< Spatial tendon attachment data, write only, see PxScene::applyArticulationData()
};
};
/**
\brief These flags determine what data is read or written to the internal articulation data via cache.
@see PxArticulationCache PxArticulationReducedCoordinate::copyInternalStateToCache PxArticulationReducedCoordinate::applyCache
*/
class PxArticulationCacheFlag
{
public:
enum Enum
{
eVELOCITY = (1 << 0), //!< The joint velocities, see PxArticulationCache::jointVelocity.
eACCELERATION = (1 << 1), //!< The joint accelerations, see PxArticulationCache::jointAcceleration.
ePOSITION = (1 << 2), //!< The joint positions, see PxArticulationCache::jointPosition.
eFORCE = (1 << 3), //!< The joint forces, see PxArticulationCache::jointForce.
eLINK_VELOCITY = (1 << 4), //!< The link velocities, see PxArticulationCache::linkVelocity.
eLINK_ACCELERATION = (1 << 5), //!< The link accelerations, see PxArticulationCache::linkAcceleration.
eROOT_TRANSFORM = (1 << 6), //!< Root link transform, see PxArticulationCache::rootLinkData.
eROOT_VELOCITIES = (1 << 7), //!< Root link velocities (read/write) and accelerations (read), see PxArticulationCache::rootLinkData.
eSENSOR_FORCES = (1 << 8), //!< The spatial sensor forces, see PxArticulationCache::sensorForces.
eJOINT_SOLVER_FORCES = (1 << 9), //!< Solver constraint joint forces, see PxArticulationCache::jointSolverForces.
eALL = (eVELOCITY | eACCELERATION | ePOSITION | eLINK_VELOCITY | eLINK_ACCELERATION | eROOT_TRANSFORM | eROOT_VELOCITIES)
};
};
typedef PxFlags<PxArticulationCacheFlag::Enum, PxU32> PxArticulationCacheFlags;
PX_FLAGS_OPERATORS(PxArticulationCacheFlag::Enum, PxU32)
#if !PX_DOXYGEN
}
#endif
#endif

View File

@@ -1,495 +0,0 @@
//
// 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-2019 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_PHYSICS_NX_ARTICULATION_JOINT
#define PX_PHYSICS_NX_ARTICULATION_JOINT
/** \addtogroup physics
@{ */
#include "PxPhysXConfig.h"
#include "common/PxBase.h"
#include "solver/PxSolverDefs.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxArticulationJointImpl;
/**
\brief The type of joint drive to use for the articulation joint.
Two drive models are currently supported. in the TARGET model, the drive spring displacement will be determined
as the rotation vector from the relative quaternion beetween child and parent, and the target quaternion.
In the ERROR model, the drive spring displacement will be taken directly from the imaginary part of the relative
quaternion. This drive model requires more computation on the part of the application, but allows driving the joint
with a spring displacement that is more than a complete rotation.
@see PxArticulationJoint
*/
struct PxArticulationJointDriveType
{
enum Enum
{
eTARGET = 0, // use the quaternion as the drive target
eERROR = 1 // use the vector part of the quaternion as the drive error.
};
};
class PxArticulationJointBase : public PxBase
{
public:
/**
\brief get the parent articulation link to which this articulation joint belongs
\return the articulation link to which this joint belongs
*/
virtual PxArticulationLink& getParentArticulationLink() const = 0;
/**
\brief set the joint pose in the parent frame
\param[in] pose the joint pose in the parent frame
<b>Default:</b> the identity matrix
@see getParentPose()
*/
virtual void setParentPose(const PxTransform& pose) = 0;
/**
\brief get the joint pose in the parent frame
\return the joint pose in the parent frame
@see setParentPose()
*/
virtual PxTransform getParentPose() const = 0;
/**
\brief get the child articulation link to which this articulation joint belongs
\return the articulation link to which this joint belongs
*/
virtual PxArticulationLink& getChildArticulationLink() const = 0;
/**
\brief set the joint pose in the child frame
\param[in] pose the joint pose in the child frame
<b>Default:</b> the identity matrix
@see getChildPose()
*/
virtual void setChildPose(const PxTransform& pose) = 0;
/**
\brief get the joint pose in the child frame
\return the joint pose in the child frame
@see setChildPose()
*/
virtual PxTransform getChildPose() const = 0;
virtual PxArticulationJointImpl* getImpl() = 0;
virtual const PxArticulationJointImpl* getImpl() const = 0;
virtual ~PxArticulationJointBase() {}
private:
protected:
PX_INLINE PxArticulationJointBase(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags) {}
PX_INLINE PxArticulationJointBase(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxArticulationJointBase", name) || PxBase::isKindOf(name); }
};
/**
\brief a joint between two links in an articulation.
The joint model is very similar to a PxSphericalJoint with swing and twist limits,
and an implicit drive model.
@see PxArticulation PxArticulationLink
*/
class PxArticulationJoint : public PxArticulationJointBase
{
public:
/**
\brief set the target drive
This is the target position for the joint drive, measured in the parent constraint frame.
\param[in] orientation the target orientation for the joint
<b>Range:</b> a unit quaternion
<b>Default:</b> the identity quaternion
@see getTargetOrientation()
*/
virtual void setTargetOrientation(const PxQuat& orientation) = 0;
/**
\brief get the target drive position
\return the joint drive target position
@see setTargetOrientation()
*/
virtual PxQuat getTargetOrientation() const = 0;
/**
\brief set the target drive velocity
This is the target velocity for the joint drive, measured in the parent constraint frame
\param[in] velocity the target velocity for the joint
<b>Default:</b> the zero vector
@see getTargetVelocity()
*/
virtual void setTargetVelocity(const PxVec3& velocity) = 0;
/**
\brief get the target drive velocity
\return the target velocity for the joint
@see setTargetVelocity()
*/
virtual PxVec3 getTargetVelocity() const = 0;
/**
\brief set the drive type
\param[in] driveType the drive type for the joint
<b>Default:</b> PxArticulationJointDriveType::eTARGET
@see getDriveType()
*/
virtual void setDriveType(PxArticulationJointDriveType::Enum driveType) = 0;
/**
\brief get the drive type
\return the drive type
@see setDriveType()
*/
virtual PxArticulationJointDriveType::Enum getDriveType() const = 0;
/**
\brief set the drive strength of the joint acceleration spring.
The acceleration generated by the spring drive is proportional to
this value and the angle between the drive target position and the
current position.
\param[in] spring the spring strength of the joint
<b>Range:</b> [0, PX_MAX_F32)<br>
<b>Default:</b> 0.0
@see getStiffness()
*/
virtual void setStiffness(PxReal spring) = 0;
/**
\brief get the drive strength of the joint acceleration spring
\return the spring strength of the joint
@see setStiffness()
*/
virtual PxReal getStiffness() const = 0;
/**
\brief set the damping of the joint acceleration spring
The acceleration generated by the spring drive is proportional to
this value and the difference between the angular velocity of the
joint and the target drive velocity.
\param[in] damping the damping of the joint drive
<b>Range:</b> [0, PX_MAX_F32)<br>
<b>Default:</b> 0.0
@see getDamping()
*/
virtual void setDamping(PxReal damping) = 0;
/**
\brief get the damping of the joint acceleration spring
@see setDamping()
*/
virtual PxReal getDamping() const = 0;
/**
\brief set the internal compliance
Compliance determines the extent to which the joint resists acceleration.
There are separate values for resistance to accelerations caused by external
forces such as gravity and contact forces, and internal forces generated from
other joints.
A low compliance means that forces have little effect, a compliance of 1 means
the joint does not resist such forces at all.
\param[in] compliance the compliance to internal forces
<b> Range: (0, 1]</b>
<b> Default:</b> 0.0
@see getInternalCompliance()
*/
virtual void setInternalCompliance(PxReal compliance) = 0;
/**
\brief get the internal compliance
\return the compliance to internal forces
@see setInternalCompliance()
*/
virtual PxReal getInternalCompliance() const = 0;
/**
\brief get the drive external compliance
Compliance determines the extent to which the joint resists acceleration.
There are separate values for resistance to accelerations caused by external
forces such as gravity and contact forces, and internal forces generated from
other joints.
A low compliance means that forces have little effect, a compliance of 1 means
the joint does not resist such forces at all.
\param[in] compliance the compliance to external forces
<b> Range: (0, 1]</b>
<b> Default:</b> 0.0
@see getExternalCompliance()
*/
virtual void setExternalCompliance(PxReal compliance) = 0;
/**
\brief get the drive external compliance
\return the compliance to external forces
@see setExternalCompliance()
*/
virtual PxReal getExternalCompliance() const = 0;
/**
\brief set the extents of the cone limit. The extents are measured in the frame
of the parent.
Note that very small or highly elliptical limit cones may result in jitter.
\param[in] zLimit the allowed extent of rotation around the z-axis
\param[in] yLimit the allowed extent of rotation around the y-axis
<b> Range:</b> ( (0, Pi), (0, Pi) )
<b> Default:</b> (Pi/4, Pi/4)
\note Please note the order of zLimit and yLimit.
*/
virtual void setSwingLimit(PxReal zLimit, PxReal yLimit) = 0;
/**
\brief get the extents for the swing limit cone
\param[out] zLimit the allowed extent of rotation around the z-axis
\param[out] yLimit the allowed extent of rotation around the y-axis
\note Please note the order of zLimit and yLimit.
@see setSwingLimit()
*/
virtual void getSwingLimit(PxReal& zLimit, PxReal& yLimit) const = 0;
/**
\brief set the tangential spring for the limit cone
<b> Range:</b> ([0, PX_MAX_F32), [0, PX_MAX_F32))
<b> Default:</b> (0.0, 0.0)
*/
virtual void setTangentialStiffness(PxReal spring) = 0;
/**
\brief get the tangential spring for the swing limit cone
\return the tangential spring
@see setTangentialStiffness()
*/
virtual PxReal getTangentialStiffness() const = 0;
/**
\brief set the tangential damping for the limit cone
<b> Range:</b> ([0, PX_MAX_F32), [0, PX_MAX_F32))
<b> Default:</b> (0.0, 0.0)
*/
virtual void setTangentialDamping(PxReal damping) = 0;
/**
\brief get the tangential damping for the swing limit cone
\return the tangential damping
@see setTangentialDamping()
*/
virtual PxReal getTangentialDamping() const = 0;
/**
\brief set the contact distance for the swing limit
The contact distance should be less than either limit angle.
<b> Range:</b> [0, Pi]
<b> Default:</b> 0.05 radians
@see getSwingLimitContactDistance()
*/
virtual void setSwingLimitContactDistance(PxReal contactDistance) = 0;
/**
\brief get the contact distance for the swing limit
\return the contact distance for the swing limit cone
@see setSwingLimitContactDistance()
*/
virtual PxReal getSwingLimitContactDistance() const = 0;
/**
\brief set the flag which enables the swing limit
\param[in] enabled whether the limit is enabled
<b>Default:</b> false
@see getSwingLimitEnabled()
*/
virtual void setSwingLimitEnabled(bool enabled) = 0;
/**
\brief get the flag which enables the swing limit
\return whether the swing limit is enabled
@see setSwingLimitEnabled()
*/
virtual bool getSwingLimitEnabled() const = 0;
/**
\brief set the bounds of the twistLimit
\param[in] lower the lower extent of the twist limit
\param[in] upper the upper extent of the twist limit
<b> Range: (-Pi, Pi)</b>
<b> Default:</b> (-Pi/4, Pi/4)
The lower limit value must be less than the upper limit if the limit is enabled
@see getTwistLimit()
*/
virtual void setTwistLimit(PxReal lower, PxReal upper) = 0;
/**
\brief get the bounds of the twistLimit
\param[out] lower the lower extent of the twist limit
\param[out] upper the upper extent of the twist limit
@see setTwistLimit()
*/
virtual void getTwistLimit(PxReal &lower, PxReal &upper) const = 0;
/**
\brief set the flag which enables the twist limit
\param[in] enabled whether the twist limit is enabled
<b>Default:</b> false
@see getTwistLimitEnabled()
*/
virtual void setTwistLimitEnabled(bool enabled) = 0;
/**
\brief get the twistLimitEnabled flag
\return whether the twist limit is enabled
@see setTwistLimitEnabled()
*/
virtual bool getTwistLimitEnabled() const = 0;
/**
\brief set the contact distance for the swing limit
The contact distance should be less than half the distance between the upper and lower limits.
<b> Range:</b> [0, Pi)
<b> Default:</b> 0.05 radians
@see getTwistLimitContactDistance()
*/
virtual void setTwistLimitContactDistance(PxReal contactDistance) = 0;
/**
\brief get the contact distance for the swing limit
\return the contact distance for the twist limit
@see setTwistLimitContactDistance()
*/
virtual PxReal getTwistLimitContactDistance() const = 0;
virtual const char* getConcreteTypeName() const { return "PxArticulationJoint"; }
protected:
PX_INLINE PxArticulationJoint(PxType concreteType, PxBaseFlags baseFlags) : PxArticulationJointBase(concreteType, baseFlags) {}
PX_INLINE PxArticulationJoint(PxBaseFlags baseFlags) : PxArticulationJointBase(baseFlags) {}
virtual ~PxArticulationJoint() {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxArticulationJoint", name) || PxArticulationJointBase::isKindOf(name); }
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@@ -1,4 +1,3 @@
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
@@ -11,7 +10,7 @@
// 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
// 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
@@ -23,20 +22,18 @@
// (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-2019 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2008-2023 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_PHYSICS_NX_ARTICULATION_JOINT_RC
#define PX_PHYSICS_NX_ARTICULATION_JOINT_RC
#ifndef PX_ARTICULATION_JOINT_RC_H
#define PX_ARTICULATION_JOINT_RC_H
/** \addtogroup physics
@{ */
#if 1
#include "PxPhysXConfig.h"
#include "common/PxBase.h"
#include "PxArticulationJoint.h"
#include "solver/PxSolverDefs.h"
#if !PX_DOXYGEN
namespace physx
@@ -44,44 +41,482 @@ namespace physx
#endif
/**
\brief a joint between two links in an articulation.
\brief A joint between two links in an articulation.
The joint model is very similar to a PxSphericalJoint with swing and twist limits,
and an implicit drive model.
@see PxArticulation PxArticulationLink
@see PxArticulationReducedCoordinate, PxArticulationLink
*/
class PxArticulationJointReducedCoordinate : public PxArticulationJointBase
class PxArticulationJointReducedCoordinate : public PxBase
{
public:
virtual void setJointType(PxArticulationJointType::Enum jointType) = 0;
virtual PxArticulationJointType::Enum getJointType() const = 0;
/**
\brief Gets the parent articulation link of this joint.
virtual void setMotion(PxArticulationAxis::Enum axis, PxArticulationMotion::Enum motion) = 0;
virtual PxArticulationMotion::Enum getMotion(PxArticulationAxis::Enum axis) const = 0;
\return The parent link.
*/
virtual PxArticulationLink& getParentArticulationLink() const = 0;
virtual void setLimit(PxArticulationAxis::Enum axis, const PxReal lowLimit, const PxReal highLimit) = 0;
virtual void getLimit(PxArticulationAxis::Enum axis, PxReal& lowLimit, PxReal& highLimit) = 0;
virtual void setDrive(PxArticulationAxis::Enum axis, const PxReal stiffness, const PxReal damping, const PxReal maxForce, PxArticulationDriveType::Enum driveType = PxArticulationDriveType::eFORCE) = 0;
virtual void getDrive(PxArticulationAxis::Enum axis, PxReal& stiffness, PxReal& damping, PxReal& maxForce, PxArticulationDriveType::Enum& driveType) = 0;
virtual void setDriveTarget(PxArticulationAxis::Enum axis, const PxReal target) = 0;
virtual void setDriveVelocity(PxArticulationAxis::Enum axis, const PxReal targetVel) = 0;
virtual PxReal getDriveTarget(PxArticulationAxis::Enum axis) = 0;
virtual PxReal getDriveVelocity(PxArticulationAxis::Enum axis) = 0;
/**
\brief Sets the joint pose in the parent link actor frame.
virtual void setFrictionCoefficient(const PxReal coefficient) = 0;
virtual PxReal getFrictionCoefficient() const = 0;
\param[in] pose The joint pose.
<b>Default:</b> The identity transform.
\note This call is not allowed while the simulation is running.
@see getParentPose
*/
virtual void setParentPose(const PxTransform& pose) = 0;
/**
\brief Gets the joint pose in the parent link actor frame.
\return The joint pose.
@see setParentPose
*/
virtual PxTransform getParentPose() const = 0;
/**
\brief Gets the child articulation link of this joint.
\return The child link.
*/
virtual PxArticulationLink& getChildArticulationLink() const = 0;
/**
\brief Sets the joint pose in the child link actor frame.
\param[in] pose The joint pose.
<b>Default:</b> The identity transform.
\note This call is not allowed while the simulation is running.
@see getChildPose
*/
virtual void setChildPose(const PxTransform& pose) = 0;
/**
\brief Gets the joint pose in the child link actor frame.
\return The joint pose.
@see setChildPose
*/
virtual PxTransform getChildPose() const = 0;
/**
\brief Sets the joint type (e.g. revolute).
\param[in] jointType The joint type to set.
\note Setting the joint type is not allowed while the articulation is in a scene.
In order to set the joint type, remove and then re-add the articulation to the scene.
@see PxArticulationJointType, getJointType
*/
virtual void setJointType(PxArticulationJointType::Enum jointType) = 0;
/**
\brief Gets the joint type.
\return The joint type.
@see PxArticulationJointType, setJointType
*/
virtual PxArticulationJointType::Enum getJointType() const = 0;
/**
\brief Sets the joint motion for a given axis.
\param[in] axis The target axis.
\param[in] motion The motion type to set.
\note Setting the motion of joint axes is not allowed while the articulation is in a scene.
In order to set the motion, remove and then re-add the articulation to the scene.
@see PxArticulationAxis, PxArticulationMotion, getMotion
*/
virtual void setMotion(PxArticulationAxis::Enum axis, PxArticulationMotion::Enum motion) = 0;
/**
\brief Returns the joint motion for the given axis.
\param[in] axis The target axis.
\return The joint motion of the given axis.
@see PxArticulationAxis, PxArticulationMotion, setMotion
*/
virtual PxArticulationMotion::Enum getMotion(PxArticulationAxis::Enum axis) const = 0;
/**
\brief Sets the joint limits for a given axis.
- The motion of the corresponding axis should be set to PxArticulationMotion::eLIMITED in order for the limits to be enforced.
- The lower limit should be strictly smaller than the higher limit. If the limits should be equal, use PxArticulationMotion::eLOCKED
and an appropriate offset in the parent/child joint frames.
\param[in] axis The target axis.
\param[in] lowLimit The lower joint limit.<br>
<b>Range:</b> [-PX_MAX_F32, highLimit)<br>
<b>Default:</b> 0.0
\param[in] highLimit The higher joint limit.<br>
<b>Range:</b> (lowLimit, PX_MAX_F32]<br>
<b>Default:</b> 0.0
\note This call is not allowed while the simulation is running.
\deprecated Use #setLimitParams instead. Deprecated since PhysX version 5.1.
@see setLimitParams, PxArticulationAxis
*/
PX_DEPRECATED PX_FORCE_INLINE void setLimit(PxArticulationAxis::Enum axis, const PxReal lowLimit, const PxReal highLimit)
{
setLimitParams(axis, PxArticulationLimit(lowLimit, highLimit));
}
/**
\brief Returns the joint limits for a given axis.
\param[in] axis The target axis.
\param[out] lowLimit The lower joint limit.
\param[out] highLimit The higher joint limit.
\deprecated Use #getLimitParams instead. Deprecated since PhysX version 5.1.
@see getLimitParams, PxArticulationAxis
*/
PX_DEPRECATED PX_FORCE_INLINE void getLimit(PxArticulationAxis::Enum axis, PxReal& lowLimit, PxReal& highLimit) const
{
PxArticulationLimit pair = getLimitParams(axis);
lowLimit = pair.low;
highLimit = pair.high;
}
/**
\brief Sets the joint limits for a given axis.
- The motion of the corresponding axis should be set to PxArticulationMotion::eLIMITED in order for the limits to be enforced.
- The lower limit should be strictly smaller than the higher limit. If the limits should be equal, use PxArticulationMotion::eLOCKED
and an appropriate offset in the parent/child joint frames.
\param[in] axis The target axis.
\param[in] limit The joint limits.
\note This call is not allowed while the simulation is running.
\note For spherical joints, limit.min and limit.max must both be in range [-Pi, Pi].
@see getLimitParams, PxArticulationAxis, PxArticulationLimit
*/
virtual void setLimitParams(PxArticulationAxis::Enum axis, const PxArticulationLimit& limit) = 0;
/**
\brief Returns the joint limits for a given axis.
\param[in] axis The target axis.
\return The joint limits.
@see setLimitParams, PxArticulationAxis, PxArticulationLimit
*/
virtual PxArticulationLimit getLimitParams(PxArticulationAxis::Enum axis) const = 0;
/**
\brief Configures a joint drive for the given axis.
See PxArticulationDrive for parameter details; and the manual for further information, and the drives' implicit spring-damper (i.e. PD control) implementation in particular.
\param[in] axis The target axis.
\param[in] stiffness The drive stiffness, i.e. the proportional gain of the implicit PD controller.<br>
<b>Range:</b> [0, PX_MAX_F32]<br>
<b>Default:</b> 0.0
\param[in] damping The drive damping, i.e. the derivative gain of the implicit PD controller.<br>
<b>Range:</b> [0, PX_MAX_F32]<br>
<b>Default:</b> 0.0
\param[in] maxForce The force limit of the drive (this parameter also limits the force for an acceleration-type drive).<br>
<b>Range:</b> [0, PX_MAX_F32]<br>
<b>Default:</b> 0.0
\param[in] driveType The drive type, @see PxArticulationDriveType.
\note This call is not allowed while the simulation is running.
\deprecated Use #setDriveParams instead. Deprecated since PhysX version 5.1.
@see setDriveParams, PxArticulationAxis, PxArticulationDriveType, PxArticulationDrive, PxArticulationFlag::eDRIVE_LIMITS_ARE_FORCES
*/
PX_DEPRECATED PX_FORCE_INLINE void setDrive(PxArticulationAxis::Enum axis, const PxReal stiffness, const PxReal damping, const PxReal maxForce, PxArticulationDriveType::Enum driveType = PxArticulationDriveType::eFORCE)
{
setDriveParams(axis, PxArticulationDrive(stiffness, damping, maxForce, driveType));
}
/**
\brief Gets the joint drive configuration for the given axis.
\param[in] axis The motion axis.
\param[out] stiffness The drive stiffness.
\param[out] damping The drive damping.
\param[out] maxForce The force limit.
\param[out] driveType The drive type.
\deprecated Use #getDriveParams instead. Deprecated since PhysX version 5.1.
@see getDriveParams, PxArticulationAxis, PxArticulationDriveType, PxArticulationDrive
*/
PX_DEPRECATED PX_FORCE_INLINE void getDrive(PxArticulationAxis::Enum axis, PxReal& stiffness, PxReal& damping, PxReal& maxForce, PxArticulationDriveType::Enum& driveType) const
{
PxArticulationDrive drive = getDriveParams(axis);
stiffness = drive.stiffness;
damping = drive.damping;
maxForce = drive.maxForce;
driveType = drive.driveType;
}
/**
\brief Configures a joint drive for the given axis.
See PxArticulationDrive for parameter details; and the manual for further information, and the drives' implicit spring-damper (i.e. PD control) implementation in particular.
\param[in] axis The target axis.
\param[in] drive The drive parameters
\note This call is not allowed while the simulation is running.
@see getDriveParams, PxArticulationAxis, PxArticulationDrive
*/
virtual void setDriveParams(PxArticulationAxis::Enum axis, const PxArticulationDrive& drive) = 0;
/**
\brief Gets the joint drive configuration for the given axis.
\param[in] axis The target axis.
\return The drive parameters.
@see setDriveParams, PxArticulationAxis, PxArticulationDrive
*/
virtual PxArticulationDrive getDriveParams(PxArticulationAxis::Enum axis) const = 0;
/**
\brief Sets the joint drive position target for the given axis.
The target units are linear units (equivalent to scene units) for a translational axis, or rad for a rotational axis.
\param[in] axis The target axis.
\param[in] target The target position.
\param[in] autowake 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.
\note This call is not allowed while the simulation is running.
\note For spherical joints, target must be in range [-Pi, Pi].
\note The target is specified in the parent frame of the joint. If Gp, Gc are the parent and child actor poses in the world frame and Lp, Lc are the parent and child joint frames expressed in the parent and child actor frames then the joint will drive the parent and child links to poses that obey Gp * Lp * J = Gc * Lc. For joints restricted to angular motion, J has the form PxTranfsorm(PxVec3(PxZero), PxExp(PxVec3(twistTarget, swing1Target, swing2Target))). For joints restricted to linear motion, J has the form PxTransform(PxVec3(XTarget, YTarget, ZTarget), PxQuat(PxIdentity)).
\note For spherical joints with more than 1 degree of freedom, the joint target angles taken together can collectively represent a rotation of greater than Pi around a vector. When this happens the rotation that matches the joint drive target is not the shortest path rotation. The joint pose J that is the outcome after driving to the target pose will always be the equivalent of the shortest path rotation.
@see PxArticulationAxis, getDriveTarget
*/
virtual void setDriveTarget(PxArticulationAxis::Enum axis, const PxReal target, bool autowake = true) = 0;
/**
\brief Returns the joint drive position target for the given axis.
\param[in] axis The target axis.
\return The target position.
@see PxArticulationAxis, setDriveTarget
*/
virtual PxReal getDriveTarget(PxArticulationAxis::Enum axis) const = 0;
/**
\brief Sets the joint drive velocity target for the given axis.
The target units are linear units (equivalent to scene units) per second for a translational axis, or radians per second for a rotational axis.
\param[in] axis The target axis.
\param[in] targetVel The target velocity.
\param[in] autowake 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.
\note This call is not allowed while the simulation is running.
@see PxArticulationAxis, getDriveVelocity
*/
virtual void setDriveVelocity(PxArticulationAxis::Enum axis, const PxReal targetVel, bool autowake = true) = 0;
/**
\brief Returns the joint drive velocity target for the given axis.
\param[in] axis The target axis.
\return The target velocity.
@see PxArticulationAxis, setDriveVelocity
*/
virtual PxReal getDriveVelocity(PxArticulationAxis::Enum axis) const = 0;
/**
\brief Sets the joint armature for the given axis.
- The armature is directly added to the joint-space spatial inertia of the corresponding axis.
- The armature is in mass units for a prismatic (i.e. linear) joint, and in mass units * (scene linear units)^2 for a rotational joint.
\param[in] axis The target axis.
\param[in] armature The joint axis armature.
\note This call is not allowed while the simulation is running.
@see PxArticulationAxis, getArmature
*/
virtual void setArmature(PxArticulationAxis::Enum axis, const PxReal armature) = 0;
/**
\brief Gets the joint armature for the given axis.
\param[in] axis The target axis.
\return The armature set on the given axis.
@see PxArticulationAxis, setArmature
*/
virtual PxReal getArmature(PxArticulationAxis::Enum axis) const = 0;
/**
\brief Sets the joint friction coefficient, which applies to all joint axes.
- The joint friction is unitless and relates the magnitude of the spatial force [F_trans, T_trans] transmitted from parent to child link to
the maximal friction force F_resist that may be applied by the solver to resist joint motion, per axis; i.e. |F_resist| <= coefficient * (|F_trans| + |T_trans|),
where F_resist may refer to a linear force or torque depending on the joint axis.
- The simulated friction effect is therefore similar to static and Coulomb friction. In order to simulate dynamic joint friction, use a joint drive with
zero stiffness and zero velocity target, and an appropriately dimensioned damping parameter.
\param[in] coefficient The joint friction coefficient.
\note This call is not allowed while the simulation is running.
@see getFrictionCoefficient
*/
virtual void setFrictionCoefficient(const PxReal coefficient) = 0;
/**
\brief Gets the joint friction coefficient.
\return The joint friction coefficient.
@see setFrictionCoefficient
*/
virtual PxReal getFrictionCoefficient() const = 0;
/**
\brief Sets the maximal joint velocity enforced for all axes.
- The solver will apply appropriate joint-space impulses in order to enforce the per-axis joint-velocity limit.
- The velocity units are linear units (equivalent to scene units) per second for a translational axis, or radians per second for a rotational axis.
\param[in] maxJointV The maximal per-axis joint velocity.
\note This call is not allowed while the simulation is running.
@see getMaxJointVelocity
*/
virtual void setMaxJointVelocity(const PxReal maxJointV) = 0;
/**
\brief Gets the maximal joint velocity enforced for all axes.
\return The maximal per-axis joint velocity.
@see setMaxJointVelocity
*/
virtual PxReal getMaxJointVelocity() const = 0;
/**
\brief Sets the joint position for the given axis.
- For performance, prefer PxArticulationCache::jointPosition to set joint positions in a batch articulation state update.
- Use PxArticulationReducedCoordinate::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.
\param[in] axis The target axis.
\param[in] jointPos The joint position in linear units (equivalent to scene units) for a translational axis, or radians for a rotational axis.
\note This call is not allowed while the simulation is running.
\note For spherical joints, jointPos must be in range [-Pi, Pi].
\note Joint position is specified in the parent frame of the joint. If Gp, Gc are the parent and child actor poses in the world frame and Lp, Lc are the parent and child joint frames expressed in the parent and child actor frames then the parent and child links will be given poses that obey Gp * Lp * J = Gc * Lc with J denoting the joint pose. For joints restricted to angular motion, J has the form PxTranfsorm(PxVec3(PxZero), PxExp(PxVec3(twistPos, swing1Pos, swing2Pos))). For joints restricted to linear motion, J has the form PxTransform(PxVec3(xPos, yPos, zPos), PxQuat(PxIdentity)).
\note For spherical joints with more than 1 degree of freedom, the input joint positions taken together can collectively represent a rotation of greater than Pi around a vector. When this happens the rotation that matches the joint positions is not the shortest path rotation. The joint pose J that is the outcome of setting and applying the joint positions will always be the equivalent of the shortest path rotation.
@see PxArticulationAxis, getJointPosition, PxArticulationCache::jointPosition, PxArticulationReducedCoordinate::updateKinematic
*/
virtual void setJointPosition(PxArticulationAxis::Enum axis, const PxReal jointPos) = 0;
/**
\brief Gets the joint position for the given axis, i.e. joint degree of freedom (DOF).
For performance, prefer PxArticulationCache::jointPosition to get joint positions in a batch query.
\param[in] axis The target axis.
\return The joint position in linear units (equivalent to scene units) for a translational axis, or radians for a rotational axis.
\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.
@see PxArticulationAxis, setJointPosition, PxArticulationCache::jointPosition
*/
virtual PxReal getJointPosition(PxArticulationAxis::Enum axis) const = 0;
/**
\brief Sets the joint velocity for the given axis.
- For performance, prefer PxArticulationCache::jointVelocity to set joint velocities in a batch articulation state update.
- Use PxArticulationReducedCoordinate::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.
\param[in] axis The target axis.
\param[in] jointVel The joint velocity in linear units (equivalent to scene units) per second for a translational axis, or radians per second for a rotational axis.
\note This call is not allowed while the simulation is running.
@see PxArticulationAxis, getJointVelocity, PxArticulationCache::jointVelocity, PxArticulationReducedCoordinate::updateKinematic
*/
virtual void setJointVelocity(PxArticulationAxis::Enum axis, const PxReal jointVel) = 0;
/**
\brief Gets the joint velocity for the given axis.
For performance, prefer PxArticulationCache::jointVelocity to get joint velocities in a batch query.
\param[in] axis The target axis.
\return The joint velocity in linear units (equivalent to scene units) per second for a translational axis, or radians per second for a rotational axis.
\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.
@see PxArticulationAxis, setJointVelocity, PxArticulationCache::jointVelocity
*/
virtual PxReal getJointVelocity(PxArticulationAxis::Enum axis) const = 0;
/**
\brief Returns the string name of the dynamic type.
\return The string name.
*/
virtual const char* getConcreteTypeName() const { return "PxArticulationJointReducedCoordinate"; }
virtual void setMaxJointVelocity(const PxReal maxJointV) = 0;
virtual PxReal getMaxJointVelocity() const = 0;
virtual ~PxArticulationJointReducedCoordinate() {}
//public variables:
void* userData; //!< The user can assign this to whatever, usually to create a 1:1 relationship with a user object.
protected:
PX_INLINE PxArticulationJointReducedCoordinate(PxType concreteType, PxBaseFlags baseFlags) : PxArticulationJointBase(concreteType, baseFlags) {}
PX_INLINE PxArticulationJointReducedCoordinate(PxBaseFlags baseFlags) : PxArticulationJointBase(baseFlags) {}
virtual ~PxArticulationJointReducedCoordinate() {}
PX_INLINE PxArticulationJointReducedCoordinate(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags) {}
PX_INLINE PxArticulationJointReducedCoordinate(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxArticulationJointReducedCoordinate", name) || PxBase::isKindOf(name); }
};
@@ -89,7 +524,5 @@ namespace physx
} // namespace physx
#endif
#endif
/** @} */
/** @} */
#endif

View File

@@ -1,4 +1,3 @@
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
@@ -11,7 +10,7 @@
// 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
// 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
@@ -23,18 +22,16 @@
// (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-2019 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2008-2023 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_PHYSICS_NX_ARTICULATION_LINK
#define PX_PHYSICS_NX_ARTICULATION_LINK
#ifndef PX_ARTICULATION_LINK_H
#define PX_ARTICULATION_LINK_H
/** \addtogroup physics
@{ */
#include "PxPhysXConfig.h"
#include "PxArticulationJoint.h"
#include "PxRigidBody.h"
#if !PX_DOXYGEN
@@ -42,86 +39,155 @@ namespace physx
{
#endif
class PxArticulationBase;
/**
\brief a component of an articulation that represents a rigid body
\brief A component of an articulation that represents a rigid body.
A limited subset of the properties of PxRigidDynamic are supported. In particular, sleep properties
are attributes of the articulation rather than each individual body, damping and velocity limits
are not supported, and links may not be kinematic.
Articulation links have a restricted subset of the functionality of a PxRigidDynamic:
- They may not be kinematic, and do not support contact-force thresholds.
- Their velocity or global pose cannot be set directly, but must be set via the articulation-root and joint positions/velocities.
- Sleep state and solver iteration counts are properties of the entire articulation rather than the individual links.
@see PxArticulation PxArticulation.createLink PxArticulationJoint PxRigidBody
@see PxArticulationReducedCoordinate, PxArticulationReducedCoordinate::createLink, PxArticulationJointReducedCoordinate, PxRigidBody
*/
class PxArticulationLink : public PxRigidBody
{
public:
/**
\brief Deletes the articulation link.
\brief Releases the link from the articulation.
\note Only a leaf articulation link can be released
\note Only a leaf articulation link can be released.
\note Releasing a link is not allowed while the articulation link is in a scene. In order to release a link,
remove and then re-add the corresponding articulation to the scene.
Do not keep a reference to the deleted instance.
@see PxArticulation::createLink()
@see PxArticulationReducedCoordinate::createLink()
*/
virtual void release() = 0;
/**
\brief get the articulation to which this articulation link belongs. This returns the base class. The application should
establish which articulation implementation this actually is and upcast to that type to access non-common functionality
\brief Gets the articulation that the link is a part of.
\return the articulation to which this link belongs
\return The articulation.
@see PxArticulationReducedCoordinate
*/
virtual PxArticulationBase& getArticulation() const = 0;
virtual PxArticulationReducedCoordinate& getArticulation() const = 0;
/**
\brief Get the joint which connects this link to its parent.
\brief Gets the joint which connects this link to its parent.
\return The joint connecting the link to the parent. NULL for the root link.
@see PxArticulationJoint
@see PxArticulationJointReducedCoordinate
*/
virtual PxArticulationJointBase* getInboundJoint() const = 0;
virtual PxArticulationJointReducedCoordinate* getInboundJoint() const = 0;
/**
\brief Get the degree of freedom of the joint which connects this link to its parent.
\brief Gets the number of degrees of freedom of the joint which connects this link to its parent.
\return The degree of freeedom of the joint connecting the link to the parent. 0xffffffff for the root link.
- The root link DOF-count is defined to be 0 regardless of PxArticulationFlag::eFIX_BASE.
- The return value is only valid for articulations that are in a scene.
@see PxArticulationJoint
\return The number of degrees of freedom, or 0xFFFFFFFF if the articulation is not in a scene.
@see PxArticulationJointReducedCoordinate
*/
virtual PxU32 getInboundJointDof() const = 0;
/**
\brief Get number of child links.
\brief Gets the number of child links.
\return the number of child links
\return The number of child links.
@see getChildren()
@see getChildren
*/
virtual PxU32 getNbChildren() const = 0;
/**
\brief Get low-level link index
\brief Gets the low-level link index that may be used to index into members of PxArticulationCache.
\return low-level index
The return value is only valid for articulations that are in a scene.
\return The low-level index, or 0xFFFFFFFF if the articulation is not in a scene.
@see PxArticulationCache
*/
virtual PxU32 getLinkIndex() const = 0;
/**
\brief Retrieve all the child links.
\brief Retrieves the child links.
\param[out] userBuffer The buffer to receive articulation link pointers.
\param[in] bufferSize Size of provided user buffer.
\return Number of articulation links written to the buffer.
\param[in] startIndex Index of first child pointer to be retrieved
\param[in] bufferSize The size of the provided user buffer, use getNbChildren() for sizing.
\param[in] startIndex The index of the first child pointer to be retrieved.
@see getNbChildren()
\return The number of articulation links written to the buffer.
@see getNbChildren
*/
virtual PxU32 getChildren(PxArticulationLink** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
virtual PxU32 getChildren(PxArticulationLink** userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0;
/**
\brief Set the constraint-force-mixing scale term.
The cfm scale term is a stabilization term that helps avoid instabilities with over-constrained
configurations. It should be a small value that is multiplied by 1/mass internally to produce
an additional bias added to the unit response term in the solver.
\param[in] cfm The constraint-force-mixing scale term.
<b>Default:</b> 0.025
<b>Range:</b> [0, 1]
\note This call is not allowed while the simulation is running.
@see getCfmScale
*/
virtual void setCfmScale(const PxReal cfm) = 0;
/**
\brief Get the constraint-force-mixing scale term.
\return The constraint-force-mixing scale term.
@see setCfmScale
*/
virtual PxReal getCfmScale() const = 0;
/**
\brief Get the linear velocity of the link.
- The linear velocity is with respect to the link's center of mass and not the actor frame origin.
- For performance, prefer PxArticulationCache::linkVelocity to get link spatial velocities in a batch query.
- When the articulation state is updated via non-cache API, use PxArticulationReducedCoordinate::updateKinematic before querying velocity.
\return The linear velocity of the link.
\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.
@see PxRigidBody::getCMassLocalPose
*/
virtual PxVec3 getLinearVelocity() const = 0;
/**
\brief Get the angular velocity of the link.
- For performance, prefer PxArticulationCache::linkVelocity to get link spatial velocities in a batch query.
- When the articulation state is updated via non-cache API, use PxArticulationReducedCoordinate::updateKinematic before querying velocity.
\return The angular velocity of the link.
\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.
*/
virtual PxVec3 getAngularVelocity() const = 0;
/**
\brief Returns the string name of the dynamic type.
\return The string name.
*/
virtual const char* getConcreteTypeName() const { return "PxArticulationLink"; }
protected:

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,589 @@
// 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-2023 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_ARTICULATION_TENDON_H
#define PX_ARTICULATION_TENDON_H
/** \addtogroup physics
@{ */
#include "PxPhysXConfig.h"
#include "common/PxBase.h"
#include "solver/PxSolverDefs.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxArticulationSpatialTendon;
class PxArticulationFixedTendon;
class PxArticulationLink;
/**
\brief Defines the low/high limits of the length of a tendon.
*/
class PxArticulationTendonLimit
{
public:
PxReal lowLimit;
PxReal highLimit;
};
/**
\brief Defines a spatial tendon attachment point on a link.
*/
class PxArticulationAttachment : public PxBase
{
public:
virtual ~PxArticulationAttachment() {}
/**
\brief Sets the spring rest length for the sub-tendon from the root to this leaf attachment.
Setting this on non-leaf attachments has no effect.
\param[in] restLength The rest length of the spring.
<b>Default:</b> 0
@see getRestLength(), isLeaf()
*/
virtual void setRestLength(const PxReal restLength) = 0;
/**
\brief Gets the spring rest length for the sub-tendon from the root to this leaf attachment.
\return The rest length.
@see setRestLength()
*/
virtual PxReal getRestLength() const = 0;
/**
\brief Sets the low and high limit on the length of the sub-tendon from the root to this leaf attachment.
Setting this on non-leaf attachments has no effect.
\param[in] parameters Struct with the low and high limit.
<b>Default:</b> (PX_MAX_F32, -PX_MAX_F32) (i.e. an invalid configuration that can only work if stiffness is zero)
@see PxArticulationTendonLimit, getLimitParameters(), isLeaf()
*/
virtual void setLimitParameters(const PxArticulationTendonLimit& parameters) = 0;
/**
\brief Gets the low and high limit on the length of the sub-tendon from the root to this leaf attachment.
\return Struct with the low and high limit.
@see PxArticulationTendonLimit, setLimitParameters()
*/
virtual PxArticulationTendonLimit getLimitParameters() const = 0;
/**
\brief Sets the attachment's relative offset in the link actor frame.
\param[in] offset The relative offset in the link actor frame.
@see getRelativeOffset()
*/
virtual void setRelativeOffset(const PxVec3& offset) = 0;
/**
\brief Gets the attachment's relative offset in the link actor frame.
\return The relative offset in the link actor frame.
@see setRelativeOffset()
*/
virtual PxVec3 getRelativeOffset() const = 0;
/**
\brief Sets the attachment coefficient.
\param[in] coefficient The scale that the distance between this attachment and its parent is multiplied by when summing up the spatial tendon's length.
@see getCoefficient()
*/
virtual void setCoefficient(const PxReal coefficient) = 0;
/**
\brief Gets the attachment coefficient.
\return The scale that the distance between this attachment and its parent is multiplied by when summing up the spatial tendon's length.
@see setCoefficient()
*/
virtual PxReal getCoefficient() const = 0;
/**
\brief Gets the articulation link.
\return The articulation link that this attachment is attached to.
*/
virtual PxArticulationLink* getLink() const = 0;
/**
\brief Gets the parent attachment.
\return The parent attachment.
*/
virtual PxArticulationAttachment* getParent() const = 0;
/**
\brief Indicates that this attachment is a leaf, and thus defines a sub-tendon from the root to this attachment.
\return True: This attachment is a leaf and has zero children; False: Not a leaf.
*/
virtual bool isLeaf() const = 0;
/**
\brief Gets the spatial tendon that the attachment is a part of.
\return The tendon.
@see PxArticulationSpatialTendon
*/
virtual PxArticulationSpatialTendon* getTendon() const = 0;
/**
\brief Releases the attachment.
\note Releasing the attachment is not allowed while the articulation is in a scene. In order to
release the attachment, remove and then re-add the articulation to the scene.
@see PxArticulationSpatialTendon::createAttachment()
*/
virtual void release() = 0;
void* userData; //!< user can assign this to whatever, usually to create a 1:1 relationship with a user object.
/**
\brief Returns the string name of the dynamic type.
\return The string name.
*/
virtual const char* getConcreteTypeName() const { return "PxArticulationAttachment"; }
protected:
PX_INLINE PxArticulationAttachment(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags) {}
PX_INLINE PxArticulationAttachment(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
};
/**
\brief Defines a fixed-tendon joint on an articulation joint degree of freedom.
*/
class PxArticulationTendonJoint : public PxBase
{
public:
virtual ~PxArticulationTendonJoint() {}
/**
\brief Sets the tendon joint coefficient.
\param[in] axis The degree of freedom that the tendon joint operates on (must correspond to a degree of freedom of the associated link's incoming joint).
\param[in] coefficient The scale that the axis' joint position is multiplied by when summing up the fixed tendon's length.
\param[in] recipCoefficient The scale that the tendon's response is multiplied by when applying to this tendon joint.
\note RecipCoefficient is commonly expected to be 1/coefficient, but it can be set to different values to tune behavior; for example, zero can be used to
have a joint axis only participate in the length computation of the tendon, but not have any tendon force applied to it.
@see getCoefficient()
*/
virtual void setCoefficient(const PxArticulationAxis::Enum axis, const PxReal coefficient, const PxReal recipCoefficient) = 0;
/**
\brief Gets the tendon joint coefficient.
\param[out] axis The degree of freedom that the tendon joint operates on.
\param[out] coefficient The scale that the axis' joint position is multiplied by when summing up the fixed tendon's length.
\param[in] recipCoefficient The scale that the tendon's response is multiplied by when applying to this tendon joint.
@see setCoefficient()
*/
virtual void getCoefficient(PxArticulationAxis::Enum& axis, PxReal& coefficient, PxReal& recipCoefficient) const = 0;
/**
\brief Gets the articulation link.
\return The articulation link (and its incoming joint in particular) that this tendon joint is associated with.
*/
virtual PxArticulationLink* getLink() const = 0;
/**
\brief Gets the parent tendon joint.
\return The parent tendon joint.
*/
virtual PxArticulationTendonJoint* getParent() const = 0;
/**
\brief Gets the tendon that the joint is a part of.
\return The tendon.
@see PxArticulationFixedTendon
*/
virtual PxArticulationFixedTendon* getTendon() const = 0;
/**
\brief Releases a tendon joint.
\note Releasing a tendon joint is not allowed while the articulation is in a scene. In order to
release the joint, remove and then re-add the articulation to the scene.
@see PxArticulationFixedTendon::createTendonJoint()
*/
virtual void release() = 0;
void* userData; //!< user can assign this to whatever, usually to create a 1:1 relationship with a user object.
/**
\brief Returns the string name of the dynamic type.
\return The string name.
*/
virtual const char* getConcreteTypeName() const { return "PxArticulationTendonJoint"; }
protected:
PX_INLINE PxArticulationTendonJoint(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags) {}
PX_INLINE PxArticulationTendonJoint(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
};
/**
\brief Common API base class shared by PxArticulationSpatialTendon and PxArticulationFixedTendon.
*/
class PxArticulationTendon : public PxBase
{
public:
/**
\brief Sets the spring stiffness term acting on the tendon length.
\param[in] stiffness The spring stiffness.
<b>Default:</b> 0
@see getStiffness()
*/
virtual void setStiffness(const PxReal stiffness) = 0;
/**
\brief Gets the spring stiffness of the tendon.
\return The spring stiffness.
@see setStiffness()
*/
virtual PxReal getStiffness() const = 0;
/**
\brief Sets the damping term acting both on the tendon length and tendon-length limits.
\param[in] damping The damping term.
<b>Default:</b> 0
@see getDamping()
*/
virtual void setDamping(const PxReal damping) = 0;
/**
\brief Gets the damping term acting both on the tendon length and tendon-length limits.
\return The damping term.
@see setDamping()
*/
virtual PxReal getDamping() const = 0;
/**
\brief Sets the limit stiffness term acting on the tendon's length limits.
For spatial tendons, this parameter applies to all its leaf attachments / sub-tendons.
\param[in] stiffness The limit stiffness term.
<b>Default:</b> 0
@see getLimitStiffness()
*/
virtual void setLimitStiffness(const PxReal stiffness) = 0;
/**
\brief Gets the limit stiffness term acting on the tendon's length limits.
For spatial tendons, this parameter applies to all its leaf attachments / sub-tendons.
\return The limit stiffness term.
@see setLimitStiffness()
*/
virtual PxReal getLimitStiffness() const = 0;
/**
\brief Sets the length offset term for the tendon.
An offset defines an amount to be added to the accumulated length computed for the tendon. It allows the
application to actuate the tendon by shortening or lengthening it.
\param[in] offset The offset term. <b>Default:</b> 0
\param[in] autowake 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.
@see getOffset()
*/
virtual void setOffset(const PxReal offset, bool autowake = true) = 0;
/**
\brief Gets the length offset term for the tendon.
\return The offset term.
@see setOffset()
*/
virtual PxReal getOffset() const = 0;
/**
\brief Gets the articulation that the tendon is a part of.
\return The articulation.
@see PxArticulationReducedCoordinate
*/
virtual PxArticulationReducedCoordinate* getArticulation() const = 0;
/**
\brief Releases a tendon to remove it from the articulation and free its associated memory.
When an articulation is released, its attached tendons are automatically released.
\note Releasing a tendon is not allowed while the articulation is in a scene. In order to
release the tendon, remove and then re-add the articulation to the scene.
*/
virtual void release() = 0;
virtual ~PxArticulationTendon() {}
void* userData; //!< user can assign this to whatever, usually to create a 1:1 relationship with a user object.
protected:
PX_INLINE PxArticulationTendon(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags) {}
PX_INLINE PxArticulationTendon(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
};
/**
\brief A spatial tendon that attaches to an articulation.
A spatial tendon attaches to multiple links in an articulation using a set of PxArticulationAttachments.
The tendon is defined as a tree of attachment points, where each attachment can have an arbitrary number of children.
Each leaf of the attachment tree defines a subtendon between itself and the root attachment. The subtendon then
applies forces at the leaf, and an equal but opposing force at the root, in order to satisfy the spring-damper and limit
constraints that the user sets up. Attachments in between the root and leaf do not exert any force on the articulation,
but define the geometry of the tendon from which the length is computed together with the attachment coefficients.
*/
class PxArticulationSpatialTendon : public PxArticulationTendon
{
public:
/**
\brief Creates an articulation attachment and adds it to the list of children in the parent attachment.
Creating an attachment is not allowed while the articulation is in a scene. In order to
add the attachment, remove and then re-add the articulation to the scene.
\param[in] parent The parent attachment. Can be NULL for the root attachment of a tendon.
\param[in] coefficient A user-defined scale that the accumulated length is scaled by.
\param[in] relativeOffset An offset vector in the link's actor frame to the point where the tendon attachment is attached to the link.
\param[in] link The link that this attachment is associated with.
\return The newly-created attachment if creation was successful, otherwise a null pointer.
@see releaseAttachment()
*/
virtual PxArticulationAttachment* createAttachment(PxArticulationAttachment* parent, const PxReal coefficient, const PxVec3 relativeOffset, PxArticulationLink* link) = 0;
/**
\brief Fills a user-provided buffer of attachment pointers with the set of attachments.
\param[in] userBuffer The user-provided buffer.
\param[in] bufferSize The size of the buffer. If this is not large enough to contain all the pointers to attachments,
only as many as can fit are written. Use getNbAttachments to size for all attachments.
\param[in] startIndex Index of first attachment pointer to be retrieved.
\return The number of attachments that were filled into the user buffer.
@see getNbAttachments
*/
virtual PxU32 getAttachments(PxArticulationAttachment** userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0;
/**
\brief Returns the number of attachments in the tendon.
\return The number of attachments.
*/
virtual PxU32 getNbAttachments() const = 0;
/**
\brief Returns the string name of the dynamic type.
\return The string name.
*/
virtual const char* getConcreteTypeName() const { return "PxArticulationSpatialTendon"; }
virtual ~PxArticulationSpatialTendon() {}
protected:
PX_INLINE PxArticulationSpatialTendon(PxType concreteType, PxBaseFlags baseFlags) : PxArticulationTendon(concreteType, baseFlags) {}
PX_INLINE PxArticulationSpatialTendon(PxBaseFlags baseFlags) : PxArticulationTendon(baseFlags) {}
};
/**
\brief A fixed tendon that can be used to link multiple degrees of freedom of multiple articulation joints via length and limit constraints.
Fixed tendons allow the simulation of coupled relationships between joint degrees of freedom in an articulation. Fixed tendons do not allow
linking arbitrary joint axes of the articulation: The respective joints must all be directly connected to each other in the articulation structure,
i.e. each of the joints in the tendon must be connected by a single articulation link to another joint in the same tendon. This implies both that
1) fixed tendons can branch along a branching articulation; and 2) they cannot be used to create relationships between axes in a spherical joint with
more than one degree of freedom. Locked joint axes or fixed joints are currently not supported.
*/
class PxArticulationFixedTendon : public PxArticulationTendon
{
public:
/**
\brief Creates an articulation tendon joint and adds it to the list of children in the parent tendon joint.
Creating a tendon joint is not allowed while the articulation is in a scene. In order to
add the joint, remove and then re-add the articulation to the scene.
\param[in] parent The parent tendon joint. Can be NULL for the root tendon joint of a tendon.
\param[in] axis The degree of freedom that this tendon joint is associated with.
\param[in] coefficient A user-defined scale that the accumulated tendon length is scaled by.
\param[in] recipCoefficient The scale that the tendon's response is multiplied by when applying to this tendon joint.
\param[in] link The link (and the link's incoming joint in particular) that this tendon joint is associated with.
\return The newly-created tendon joint if creation was successful, otherwise a null pointer.
\note
- The axis motion must not be configured as PxArticulationMotion::eLOCKED.
- The axis cannot be part of a fixed joint, i.e. joint configured as PxArticulationJointType::eFIX.
@see PxArticulationTendonJoint PxArticulationAxis
*/
virtual PxArticulationTendonJoint* createTendonJoint(PxArticulationTendonJoint* parent, PxArticulationAxis::Enum axis, const PxReal coefficient, const PxReal recipCoefficient, PxArticulationLink* link) = 0;
/**
\brief Fills a user-provided buffer of tendon-joint pointers with the set of tendon joints.
\param[in] userBuffer The user-provided buffer.
\param[in] bufferSize The size of the buffer. If this is not large enough to contain all the pointers to tendon joints,
only as many as can fit are written. Use getNbTendonJoints to size for all tendon joints.
\param[in] startIndex Index of first tendon joint pointer to be retrieved.
\return The number of tendon joints filled into the user buffer.
@see getNbTendonJoints
*/
virtual PxU32 getTendonJoints(PxArticulationTendonJoint** userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0;
/**
\brief Returns the number of tendon joints in the tendon.
\return The number of tendon joints.
*/
virtual PxU32 getNbTendonJoints() const = 0;
/**
\brief Sets the spring rest length of the tendon.
The accumulated "length" of a fixed tendon is a linear combination of the joint axis positions that the tendon is
associated with, scaled by the respective tendon joints' coefficients. As such, when the joint positions of all
joints are zero, the accumulated length of a fixed tendon is zero.
The spring of the tendon is not exerting any force on the articulation when the rest length is equal to the
tendon's accumulated length plus the tendon offset.
\param[in] restLength The spring rest length of the tendon.
@see getRestLength()
*/
virtual void setRestLength(const PxReal restLength) = 0;
/**
\brief Gets the spring rest length of the tendon.
\return The spring rest length of the tendon.
@see setRestLength()
*/
virtual PxReal getRestLength() const = 0;
/**
\brief Sets the low and high limit on the length of the tendon.
\param[in] parameter Struct with the low and high limit.
The limits, together with the damping and limit stiffness parameters, act on the accumulated length of the tendon.
@see PxArticulationTendonLimit getLimitParameters() setRestLength()
*/
virtual void setLimitParameters(const PxArticulationTendonLimit& parameter) = 0;
/**
\brief Gets the low and high limit on the length of the tendon.
\return Struct with the low and high limit.
@see PxArticulationTendonLimit setLimitParameters()
*/
virtual PxArticulationTendonLimit getLimitParameters() const = 0;
/**
\brief Returns the string name of the dynamic type.
\return The string name.
*/
virtual const char* getConcreteTypeName() const { return "PxArticulationFixedTendon"; }
virtual ~PxArticulationFixedTendon() {}
protected:
PX_INLINE PxArticulationFixedTendon(PxType concreteType, PxBaseFlags baseFlags) : PxArticulationTendon(concreteType, baseFlags) {}
PX_INLINE PxArticulationFixedTendon(PxBaseFlags baseFlags) : PxArticulationTendon(baseFlags) {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@@ -0,0 +1,120 @@
// 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-2023 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_ARTICULATION_TENDON_DATA_H
#define PX_ARTICULATION_TENDON_DATA_H
#include "foundation/PxSimpleTypes.h"
#include "foundation/PxVec3.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief PxGpuSpatialTendonData
This data structure is to be used by the direct GPU API for spatial tendon data updates.
@see PxArticulationSpatialTendon PxScene::copyArticulationData PxScene::applyArticulationData
*/
PX_ALIGN_PREFIX(16)
class PxGpuSpatialTendonData
{
public:
PxReal stiffness;
PxReal damping;
PxReal limitStiffness;
PxReal offset;
}
PX_ALIGN_SUFFIX(16);
/**
\brief PxGpuFixedTendonData
This data structure is to be used by the direct GPU API for fixed tendon data updates.
@see PxArticulationFixedTendon PxScene::copyArticulationData PxScene::applyArticulationData
*/
PX_ALIGN_PREFIX(16)
class PxGpuFixedTendonData : public PxGpuSpatialTendonData
{
public:
PxReal lowLimit;
PxReal highLimit;
PxReal restLength;
PxReal padding;
}
PX_ALIGN_SUFFIX(16);
/**
\brief PxGpuTendonJointCoefficientData
This data structure is to be used by the direct GPU API for fixed tendon joint data updates.
@see PxArticulationTendonJoint PxScene::copyArticulationData PxScene::applyArticulationData
*/
PX_ALIGN_PREFIX(16)
class PxGpuTendonJointCoefficientData
{
public:
PxReal coefficient;
PxReal recipCoefficient;
PxU32 axis;
PxU32 pad;
}
PX_ALIGN_SUFFIX(16);
/**
\brief PxGpuTendonAttachmentData
This data structure is to be used by the direct GPU API for spatial tendon attachment data updates.
@see PxArticulationAttachment PxScene::copyArticulationData PxScene::applyArticulationData
*/
PX_ALIGN_PREFIX(16)
class PxGpuTendonAttachmentData
{
public:
PxVec3 relativeOffset;
PxReal restLength;
PxReal coefficient;
PxReal lowLimit;
PxReal highLimit;
PxReal padding;
}
PX_ALIGN_SUFFIX(16);
#if !PX_DOXYGEN
} // namespace physx
#endif
#endif

60
Source/ThirdParty/PhysX/PxAttachment.h vendored Normal file
View File

@@ -0,0 +1,60 @@
// 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-2023 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_ATTACHMENT_H
#define PX_ATTACHMENT_H
#include "PxConeLimitedConstraint.h"
#include "PxFiltering.h"
#include "foundation/PxVec4.h"
/** \addtogroup physics
@{
*/
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Struct to specify attachment between a particle/vertex and a rigid
*/
struct PxParticleRigidAttachment : public PxParticleRigidFilterPair
{
PX_ALIGN(16, PxVec4 mLocalPose0); //!< local pose in body frame - except for statics, these are using world positions.
PxConeLimitParams mParams; //!< Parameters to specify cone constraints
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@@ -0,0 +1,64 @@
// 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-2023 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_BASE_MATERIAL_H
#define PX_BASE_MATERIAL_H
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "common/PxBase.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Base material class.
@see PxPhysics.createMaterial PxPhysics.createFEMClothMaterial PxPhysics.createFEMSoftBodyMaterial PxPhysics.createFLIPMaterial PxPhysics.createMPMMaterial PxPhysics.createPBDMaterial
*/
class PxBaseMaterial : public PxRefCounted
{
public:
PX_INLINE PxBaseMaterial(PxType concreteType, PxBaseFlags baseFlags) : PxRefCounted(concreteType, baseFlags), userData(NULL) {}
PX_INLINE PxBaseMaterial(PxBaseFlags baseFlags) : PxRefCounted(baseFlags) {}
virtual ~PxBaseMaterial() {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxBaseMaterial", name) || PxRefCounted::isKindOf(name); }
void* userData; //!< user can assign this to whatever, usually to create a 1:1 relationship with a user object.
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@@ -1,224 +0,0 @@
//
// 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-2019 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_PHYSICS_NX_SCENEQUERY
#define PX_PHYSICS_NX_SCENEQUERY
/** \addtogroup scenequery
@{ */
#include "PxPhysXConfig.h"
#include "PxShape.h"
#include "PxBatchQueryDesc.h"
#include "PxQueryFiltering.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxBoxGeometry;
class PxSphereGeometry;
struct PxQueryCache;
/**
\brief Batched queries object. This is used to perform several queries at the same time.
\deprecated The batched query feature has been deprecated in PhysX version 3.4
@see PxScene, PxScene.createBatchQuery
*/
class PX_DEPRECATED PxBatchQuery
{
public:
/**
\brief Executes batched queries.
*/
virtual void execute() = 0;
/**
\brief Gets the prefilter shader in use for this scene query.
\return Prefilter shader.
@see PxBatchQueryDesc.preFilterShade PxBatchQueryPreFilterShader
*/
virtual PxBatchQueryPreFilterShader getPreFilterShader() const = 0;
/**
\brief Gets the postfilter shader in use for this scene query.
\return Postfilter shader.
@see PxBatchQueryDesc.preFilterShade PxBatchQueryPostFilterShader
*/
virtual PxBatchQueryPostFilterShader getPostFilterShader() const = 0;
/**
\brief Gets the shared global filter data in use for this scene query.
\return Shared filter data for filter shader.
@see getFilterShaderDataSize() PxBatchQueryDesc.filterShaderData PxBatchQueryPreFilterShader, PxBatchQueryPostFilterShader
*/
virtual const void* getFilterShaderData() const = 0;
/**
\brief Gets the size of the shared global filter data (#PxSceneDesc.filterShaderData)
\return Size of shared filter data [bytes].
@see getFilterShaderData() PxBatchQueryDesc.filterShaderDataSize PxBatchQueryPreFilterShader, PxBatchQueryPostFilterShader
*/
virtual PxU32 getFilterShaderDataSize() const = 0;
/**
\brief Sets new user memory pointers.
It is not possible to change the memory during query execute.
@see PxBatchQueryDesc
*/
virtual void setUserMemory(const PxBatchQueryMemory&) = 0;
/**
\brief Gets the user memory pointers.
@see PxBatchQueryDesc
*/
virtual const PxBatchQueryMemory& getUserMemory() = 0;
/**
\brief Releases PxBatchQuery from PxScene
@see PxScene, PxScene.createBatchQuery
*/
virtual void release() = 0;
/**
\brief Performs a raycast against objects in the scene, returns results in PxBatchQueryMemory::userRaycastResultBuffer
specified at PxBatchQuery creation time or via PxBatchQuery::setUserMemory call.
\note Touching hits are not ordered.
\note Shooting a ray from within an object leads to different results depending on the shape type. Please check the details in article SceneQuery. User can ignore such objects by using one of the provided filter mechanisms.
\param[in] origin Origin of the ray.
\param[in] unitDir Normalized direction of the ray.
\param[in] distance Length of the ray. Needs to be larger than 0.
\param[in] maxTouchHits Maximum number of hits to record in the touch buffer for this query. Default=0 reports a single blocking hit. If maxTouchHits is set to 0 all hits are treated as blocking by default.
\param[in] hitFlags Specifies which properties per hit should be computed and returned in hit array and blocking hit.
\param[in] filterData Filtering data passed to the filter shader. See #PxQueryFilterData #PxBatchQueryPreFilterShader, #PxBatchQueryPostFilterShader
\param[in] userData User can pass any value in this argument, usually to identify this particular query
\param[in] cache Cached hit shape (optional). Query is tested against cached shape first. If no hit is found the ray gets queried against the scene.
Note: Filtering is not executed for a cached shape if supplied; instead, if a hit is found, it is assumed to be a blocking hit.
Note: Using past touching hits as cache will produce incorrect behavior since the cached hit will always be treated as blocking.
\note This query call writes to a list associated with the query object and is NOT thread safe (for performance reasons there is no lock
and overlapping writes from different threads may result in undefined behavior).
@see PxQueryFilterData PxBatchQueryPreFilterShader PxBatchQueryPostFilterShader PxRaycastHit PxScene::raycast
*/
virtual void raycast(
const PxVec3& origin, const PxVec3& unitDir, PxReal distance = PX_MAX_F32, PxU16 maxTouchHits = 0,
PxHitFlags hitFlags = PxHitFlag::eDEFAULT,
const PxQueryFilterData& filterData = PxQueryFilterData(),
void* userData = NULL, const PxQueryCache* cache = NULL) = 0;
/**
\brief Performs an overlap test of a given geometry against objects in the scene, returns results in PxBatchQueryMemory::userOverlapResultBuffer
specified at PxBatchQuery creation time or via PxBatchQuery::setUserMemory call.
\note Filtering: returning eBLOCK from user filter for overlap queries will cause a warning (see #PxQueryHitType).
\param[in] geometry Geometry of object to check for overlap (supported types are: box, sphere, capsule, convex).
\param[in] pose Pose of the object.
\param[in] maxTouchHits Maximum number of hits to record in the touch buffer for this query. Default=0 reports a single blocking hit. If maxTouchHits is set to 0 all hits are treated as blocking by default.
\param[in] filterData Filtering data and simple logic. See #PxQueryFilterData #PxBatchQueryPreFilterShader, #PxBatchQueryPostFilterShader
\param[in] userData User can pass any value in this argument, usually to identify this particular query
\param[in] cache Cached hit shape (optional). Query is tested against cached shape first. If no hit is found the ray gets queried against the scene.
Note: Filtering is not executed for a cached shape if supplied; instead, if a hit is found, it is assumed to be a blocking hit.
Note: Using past touching hits as cache will produce incorrect behavior since the cached hit will always be treated as blocking.
\note eBLOCK should not be returned from user filters for overlap(). Doing so will result in undefined behavior, and a warning will be issued.
\note If the PxQueryFlag::eNO_BLOCK flag is set, the eBLOCK will instead be automatically converted to an eTOUCH and the warning suppressed.
\note This query call writes to a list associated with the query object and is NOT thread safe (for performance reasons there is no lock
and overlapping writes from different threads may result in undefined behavior).
@see PxQueryFilterData PxBatchQueryPreFilterShader PxBatchQueryPostFilterShader
*/
virtual void overlap(
const PxGeometry& geometry, const PxTransform& pose, PxU16 maxTouchHits = 0,
const PxQueryFilterData& filterData = PxQueryFilterData(), void* userData=NULL, const PxQueryCache* cache = NULL) = 0;
/**
\brief Performs a sweep test against objects in the scene, returns results in PxBatchQueryMemory::userSweepResultBuffer
specified at PxBatchQuery creation time or via PxBatchQuery::setUserMemory call.
\note Touching hits are not ordered.
\note If a shape from the scene is already overlapping with the query shape in its starting position,
the hit is returned unless eASSUME_NO_INITIAL_OVERLAP was specified.
\param[in] geometry Geometry of object to sweep (supported types are: box, sphere, capsule, convex).
\param[in] pose Pose of the sweep object.
\param[in] unitDir Normalized direction of the sweep.
\param[in] distance Sweep distance. Needs to be larger than 0. Will be clamped to PX_MAX_SWEEP_DISTANCE.
\param[in] maxTouchHits Maximum number of hits to record in the touch buffer for this query. Default=0 reports a single blocking hit. If maxTouchHits is set to 0 all hits are treated as blocking by default.
\param[in] hitFlags Specifies which properties per hit should be computed and returned in hit array and blocking hit.
\param[in] filterData Filtering data and simple logic. See #PxQueryFilterData #PxBatchQueryPreFilterShader, #PxBatchQueryPostFilterShader
\param[in] userData User can pass any value in this argument, usually to identify this particular query
\param[in] cache Cached hit shape (optional). Query is tested against cached shape first. If no hit is found the ray gets queried against the scene.
Note: Filtering is not executed for a cached shape if supplied; instead, if a hit is found, it is assumed to be a blocking hit.
Note: Using past touching hits as cache will produce incorrect behavior since the cached hit will always be treated as blocking.
\param[in] inflation This parameter creates a skin around the swept geometry which increases its extents for sweeping. The sweep will register a hit as soon as the skin touches a shape, and will return the corresponding distance and normal.
Note: ePRECISE_SWEEP doesn't support inflation. Therefore the sweep will be performed with zero inflation.
\note This query call writes to a list associated with the query object and is NOT thread safe (for performance reasons there is no lock
and overlapping writes from different threads may result in undefined behavior).
@see PxHitFlags PxQueryFilterData PxBatchQueryPreFilterShader PxBatchQueryPostFilterShader PxSweepHit
*/
virtual void sweep(
const PxGeometry& geometry, const PxTransform& pose, const PxVec3& unitDir, const PxReal distance,
PxU16 maxTouchHits = 0, PxHitFlags hitFlags = PxHitFlag::eDEFAULT,
const PxQueryFilterData& filterData = PxQueryFilterData(), void* userData=NULL, const PxQueryCache* cache = NULL,
const PxReal inflation = 0.f) = 0;
protected:
virtual ~PxBatchQuery() {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@@ -1,303 +0,0 @@
//
// 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-2019 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_PHYSICS_NX_SCENEQUERYDESC
#define PX_PHYSICS_NX_SCENEQUERYDESC
/** \addtogroup physics
@{ */
#include "PxPhysXConfig.h"
#include "PxClient.h"
#include "PxFiltering.h"
#include "PxQueryFiltering.h"
#include "foundation/PxAssert.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
struct PxSweepHit;
struct PxRaycastHit;
/**
\brief Batched query status.
\deprecated The batched query feature has been deprecated in PhysX version 3.4
*/
struct PX_DEPRECATED PxBatchQueryStatus
{
enum Enum
{
/**
\brief This is the initial state before a query starts.
*/
ePENDING = 0,
/**
\brief The query is finished; results have been written into the result and hit buffers.
*/
eSUCCESS,
/**
\brief The query results were incomplete due to touch hit buffer overflow. Blocking hit is still correct.
*/
eOVERFLOW
};
};
/**
\brief Generic struct for receiving results of single query in a batch. Gets templated on hit type PxRaycastHit, PxSweepHit or PxOverlapHit.
\deprecated The batched query feature has been deprecated in PhysX version 3.4
*/
template<typename HitType>
struct PX_DEPRECATED PxBatchQueryResult
{
HitType block; //!< Holds the closest blocking hit for a single query in a batch. Only valid if hasBlock is true.
HitType* touches; //!< This pointer will either be set to NULL for 0 nbTouches or will point
//!< into the user provided batch query results buffer specified in PxBatchQueryDesc.
PxU32 nbTouches; //!< Number of touching hits returned by this query, works in tandem with touches pointer.
void* userData; //!< Copy of the userData pointer specified in the corresponding query.
PxU8 queryStatus; //!< Takes on values from PxBatchQueryStatus::Enum.
bool hasBlock; //!< True if there was a blocking hit.
PxU16 pad; //!< pads the struct to 16 bytes.
/** \brief Computes the number of any hits in this result, blocking or touching. */
PX_INLINE PxU32 getNbAnyHits() const { return nbTouches + (hasBlock ? 1 : 0); }
/** \brief Convenience iterator used to access any hits in this result, blocking or touching. */
PX_INLINE const HitType& getAnyHit(const PxU32 index) const { PX_ASSERT(index < nbTouches + (hasBlock ? 1 : 0));
return index < nbTouches ? touches[index] : block; }
};
/** \brief Convenience typedef for the result of a batched raycast query. */
typedef PX_DEPRECATED PxBatchQueryResult<PxRaycastHit> PxRaycastQueryResult;
/** \brief Convenience typedef for the result of a batched sweep query. */
typedef PX_DEPRECATED PxBatchQueryResult<PxSweepHit> PxSweepQueryResult;
/** \brief Convenience typedef for the result of a batched overlap query. */
typedef PX_DEPRECATED PxBatchQueryResult<PxOverlapHit> PxOverlapQueryResult;
/**
\brief Struct for #PxBatchQuery memory pointers.
\deprecated The batched query feature has been deprecated in PhysX version 3.4
@see PxBatchQuery PxBatchQueryDesc
*/
struct PX_DEPRECATED PxBatchQueryMemory
{
/**
\brief The pointer to the user-allocated buffer for results of raycast queries in corresponding order of issue
\note The size should be large enough to fit the number of expected raycast queries.
@see PxRaycastQueryResult
*/
PxRaycastQueryResult* userRaycastResultBuffer;
/**
\brief The pointer to the user-allocated buffer for raycast touch hits.
\note The size of this buffer should be large enough to store PxRaycastHit.
If the buffer is too small to store hits, the related PxRaycastQueryResult.queryStatus will be set to eOVERFLOW
*/
PxRaycastHit* userRaycastTouchBuffer;
/**
\brief The pointer to the user-allocated buffer for results of sweep queries in corresponding order of issue
\note The size should be large enough to fit the number of expected sweep queries.
@see PxRaycastQueryResult
*/
PxSweepQueryResult* userSweepResultBuffer;
/**
\brief The pointer to the user-allocated buffer for sweep hits.
\note The size of this buffer should be large enough to store PxSweepHit.
If the buffer is too small to store hits, the related PxSweepQueryResult.queryStatus will be set to eOVERFLOW
*/
PxSweepHit* userSweepTouchBuffer;
/**
\brief The pointer to the user-allocated buffer for results of overlap queries in corresponding order of issue
\note The size should be large enough to fit the number of expected overlap queries.
@see PxRaycastQueryResult
*/
PxOverlapQueryResult* userOverlapResultBuffer;
/**
\brief The pointer to the user-allocated buffer for overlap hits.
\note The size of this buffer should be large enough to store the hits returned.
If the buffer is too small to store hits, the related PxOverlapQueryResult.queryStatus will be set to eABORTED
*/
PxOverlapHit* userOverlapTouchBuffer;
/** \brief Capacity of the user-allocated userRaycastTouchBuffer in elements */
PxU32 raycastTouchBufferSize;
/** \brief Capacity of the user-allocated userSweepTouchBuffer in elements */
PxU32 sweepTouchBufferSize;
/** \brief Capacity of the user-allocated userOverlapTouchBuffer in elements */
PxU32 overlapTouchBufferSize;
/** \return Capacity of the user-allocated userRaycastResultBuffer in elements (max number of raycast() calls before execute() call) */
PX_FORCE_INLINE PxU32 getMaxRaycastsPerExecute() const { return raycastResultBufferSize; }
/** \return Capacity of the user-allocated userSweepResultBuffer in elements (max number of sweep() calls before execute() call) */
PX_FORCE_INLINE PxU32 getMaxSweepsPerExecute() const { return sweepResultBufferSize; }
/** \return Capacity of the user-allocated userOverlapResultBuffer in elements (max number of overlap() calls before execute() call) */
PX_FORCE_INLINE PxU32 getMaxOverlapsPerExecute() const { return overlapResultBufferSize; }
PxBatchQueryMemory(PxU32 raycastResultBufferSize_, PxU32 sweepResultBufferSize_, PxU32 overlapResultBufferSize_) :
userRaycastResultBuffer (NULL),
userRaycastTouchBuffer (NULL),
userSweepResultBuffer (NULL),
userSweepTouchBuffer (NULL),
userOverlapResultBuffer (NULL),
userOverlapTouchBuffer (NULL),
raycastTouchBufferSize (0),
sweepTouchBufferSize (0),
overlapTouchBufferSize (0),
raycastResultBufferSize (raycastResultBufferSize_),
sweepResultBufferSize (sweepResultBufferSize_),
overlapResultBufferSize (overlapResultBufferSize_)
{
}
protected:
PxU32 raycastResultBufferSize;
PxU32 sweepResultBufferSize;
PxU32 overlapResultBufferSize;
};
/**
\brief Descriptor class for #PxBatchQuery.
\deprecated The batched query feature has been deprecated in PhysX version 3.4
@see PxBatchQuery PxSceneQueryExecuteMode
*/
class PX_DEPRECATED PxBatchQueryDesc
{
public:
/**
\brief Shared global filter data which will get passed into the filter shader.
\note The provided data will get copied to internal buffers and this copy will be used for filtering calls.
<b>Default:</b> NULL
@see PxSimulationFilterShader
*/
void* filterShaderData;
/**
\brief Size (in bytes) of the shared global filter data #filterShaderData.
<b>Default:</b> 0
@see PxSimulationFilterShader filterShaderData
*/
PxU32 filterShaderDataSize;
/**
\brief The custom preFilter shader to use for filtering.
@see PxBatchQueryPreFilterShader PxDefaultPreFilterShader
*/
PxBatchQueryPreFilterShader preFilterShader;
/**
\brief The custom postFilter shader to use for filtering.
@see PxBatchQueryPostFilterShader PxDefaultPostFilterShader
*/
PxBatchQueryPostFilterShader postFilterShader;
/**
\brief User memory buffers for the query.
@see PxBatchQueryMemory
*/
PxBatchQueryMemory queryMemory;
/**
\brief Construct a batch query with specified maximum number of queries per batch.
If the number of raycasts/sweeps/overlaps per execute exceeds the limit, the query will be discarded with a warning.
\param maxRaycastsPerExecute Maximum number of raycast() calls allowed before execute() call.
This has to match the amount of memory allocated for PxBatchQueryMemory::userRaycastResultBuffer.
\param maxSweepsPerExecute Maximum number of sweep() calls allowed before execute() call.
This has to match the amount of memory allocated for PxBatchQueryMemory::userSweepResultBuffer.
\param maxOverlapsPerExecute Maximum number of overlap() calls allowed before execute() call.
This has to match the amount of memory allocated for PxBatchQueryMemory::userOverlapResultBuffer.
*/
PX_INLINE PxBatchQueryDesc(PxU32 maxRaycastsPerExecute, PxU32 maxSweepsPerExecute, PxU32 maxOverlapsPerExecute);
PX_INLINE bool isValid() const;
};
PX_INLINE PxBatchQueryDesc::PxBatchQueryDesc(PxU32 maxRaycastsPerExecute, PxU32 maxSweepsPerExecute, PxU32 maxOverlapsPerExecute) :
filterShaderData (NULL),
filterShaderDataSize (0),
preFilterShader (NULL),
postFilterShader (NULL),
queryMemory (maxRaycastsPerExecute, maxSweepsPerExecute, maxOverlapsPerExecute)
{
}
PX_INLINE bool PxBatchQueryDesc::isValid() const
{
if ( ((filterShaderDataSize == 0) && (filterShaderData != NULL)) ||
((filterShaderDataSize > 0) && (filterShaderData == NULL)) )
return false;
return true;
}
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@@ -1,4 +1,3 @@
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
@@ -11,7 +10,7 @@
// 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
// 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
@@ -23,13 +22,12 @@
// (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-2019 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2008-2023 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_PHYSICS_BROAD_PHASE_H
#define PX_PHYSICS_BROAD_PHASE_H
#ifndef PX_BROAD_PHASE_H
#define PX_BROAD_PHASE_H
/** \addtogroup physics
@{
*/
@@ -42,7 +40,8 @@ namespace physx
{
#endif
class PxActor;
class PxBaseTask;
class PxCudaContextManager;
/**
\brief Broad phase algorithm used in the simulation
@@ -62,62 +61,31 @@ namespace physx
of eMBP when a lot of objects are moving. While eSAP can remain faster when most objects are
sleeping and eMBP can remain faster when it uses a large number of properly-defined regions,
eABP often gives the best performance on average and the best memory usage.
ePABP is a parallel implementation of ABP. It can often be the fastest (CPU) broadphase, but it
can use more memory than ABP.
eGPU is a GPU implementation of the incremental sweep and prune approach. Additionally, it uses a ABP-style
initial pair generation approach to avoid large spikes when inserting shapes. It not only has the advantage
of traditional SAP approch which is good for when many objects are sleeping, but due to being fully parallel,
it also is great when lots of shapes are moving or for runtime pair insertion and removal. It can become a
performance bottleneck if there are a very large number of shapes roughly projecting to the same values
on a given axis. If the scene has a very large number of shapes in an actor, e.g. a humanoid, it is recommended
to use an aggregate to represent multi-shape or multi-body actors to minimize stress placed on the broad phase.
*/
struct PxBroadPhaseType
{
enum Enum
{
eSAP, //!< 3-axes sweep-and-prune
eMBP, //!< Multi box pruning
eABP, //!< Automatic box pruning
eGPU,
eSAP, //!< 3-axes sweep-and-prune
eMBP, //!< Multi box pruning
eABP, //!< Automatic box pruning
ePABP, //!< Parallel automatic box pruning
eGPU, //!< GPU broad phase
eLAST
};
};
/**
\brief Broad-phase callback to receive broad-phase related events.
Each broadphase callback object is associated with a PxClientID. It is possible to register different
callbacks for different clients. The callback functions are called this way:
- for shapes/actors, the callback assigned to the actors' clients are used
- for aggregates, the callbacks assigned to clients from aggregated actors are used
\note SDK state should not be modified from within the callbacks. In particular objects should not
be created or destroyed. If state modification is needed then the changes should be stored to a buffer
and performed after the simulation step.
<b>Threading:</b> It is not necessary to make this class thread safe as it will only be called in the context of the
user thread.
@see PxSceneDesc PxScene.setBroadPhaseCallback() PxScene.getBroadPhaseCallback()
*/
class PxBroadPhaseCallback
{
public:
virtual ~PxBroadPhaseCallback() {}
/**
\brief Out-of-bounds notification.
This function is called when an object leaves the broad-phase.
\param[in] shape Shape that left the broad-phase bounds
\param[in] actor Owner actor
*/
virtual void onObjectOutOfBounds(PxShape& shape, PxActor& actor) = 0;
/**
\brief Out-of-bounds notification.
This function is called when an aggregate leaves the broad-phase.
\param[in] aggregate Aggregate that left the broad-phase bounds
*/
virtual void onObjectOutOfBounds(PxAggregate& aggregate) = 0;
};
/**
\brief "Region of interest" for the broad-phase.
@@ -129,7 +97,7 @@ namespace physx
thus collisions will be disabled for them. A PxBroadPhaseCallback out-of-bounds notification will be sent for each one
of those objects.
The total number of regions is limited by PxBroadPhaseCaps::maxNbRegions.
The total number of regions is limited by PxBroadPhaseCaps::mMaxNbRegions.
The number of regions has a direct impact on performance and memory usage, so it is recommended to experiment with
various settings to find the best combination for your game. A good default setup is to start with global bounds
@@ -140,8 +108,8 @@ namespace physx
*/
struct PxBroadPhaseRegion
{
PxBounds3 bounds; //!< Region's bounds
void* userData; //!< Region's user-provided data
PxBounds3 mBounds; //!< Region's bounds
void* mUserData; //!< Region's user-provided data
};
/**
@@ -149,11 +117,11 @@ namespace physx
*/
struct PxBroadPhaseRegionInfo
{
PxBroadPhaseRegion region; //!< User-provided region data
PxU32 nbStaticObjects; //!< Number of static objects in the region
PxU32 nbDynamicObjects; //!< Number of dynamic objects in the region
bool active; //!< True if region is currently used, i.e. it has not been removed
bool overlap; //!< True if region overlaps other regions (regions that are just touching are not considering overlapping)
PxBroadPhaseRegion mRegion; //!< User-provided region data
PxU32 mNbStaticObjects; //!< Number of static objects in the region
PxU32 mNbDynamicObjects; //!< Number of dynamic objects in the region
bool mActive; //!< True if region is currently used, i.e. it has not been removed
bool mOverlap; //!< True if region overlaps other regions (regions that are just touching are not considering overlapping)
};
/**
@@ -161,11 +129,574 @@ namespace physx
*/
struct PxBroadPhaseCaps
{
PxU32 maxNbRegions; //!< Max number of regions supported by the broad-phase
PxU32 maxNbObjects; //!< Max number of objects supported by the broad-phase
bool needsPredefinedBounds; //!< If true, broad-phase needs 'regions' to work
PxU32 mMaxNbRegions; //!< Max number of regions supported by the broad-phase (0 = explicit regions not needed)
};
/**
\brief Broadphase descriptor.
This structure is used to create a standalone broadphase. It captures all the parameters needed to
initialize a broadphase.
For the GPU broadphase (PxBroadPhaseType::eGPU) it is necessary to provide a CUDA context manager.
The kinematic filtering flags are currently not supported by the GPU broadphase. They are used to
dismiss pairs that involve kinematic objects directly within the broadphase.
\see PxCreateBroadPhase
*/
class PxBroadPhaseDesc
{
public:
PxBroadPhaseDesc(PxBroadPhaseType::Enum type = PxBroadPhaseType::eLAST) :
mType (type),
mContextID (0),
mContextManager (NULL),
mFoundLostPairsCapacity (256 * 1024),
mDiscardStaticVsKinematic (false),
mDiscardKinematicVsKinematic(false)
{}
PxBroadPhaseType::Enum mType; //!< Desired broadphase implementation
PxU64 mContextID; //!< Context ID for profiler. See PxProfilerCallback.
PxCudaContextManager* mContextManager; //!< (GPU) CUDA context manager, must be provided for PxBroadPhaseType::eGPU.
PxU32 mFoundLostPairsCapacity; //!< (GPU) Capacity of found and lost buffers allocated in GPU global memory. This is used for the found/lost pair reports in the BP.
bool mDiscardStaticVsKinematic; //!< Static-vs-kinematic filtering flag. Not supported by PxBroadPhaseType::eGPU.
bool mDiscardKinematicVsKinematic; //!< kinematic-vs-kinematic filtering flag. Not supported by PxBroadPhaseType::eGPU.
PX_INLINE bool isValid() const
{
if(PxU32(mType)>=PxBroadPhaseType::eLAST)
return false;
if(mType==PxBroadPhaseType::eGPU && !mContextManager)
return false;
return true;
}
};
typedef PxU32 PxBpIndex; //!< Broadphase index. Indexes bounds, groups and distance arrays.
typedef PxU32 PxBpFilterGroup; //!< Broadphase filter group.
#define PX_INVALID_BP_FILTER_GROUP 0xffffffff //!< Invalid broadphase filter group
/**
\brief Retrieves the filter group for static objects.
Mark static objects with this group when adding them to the broadphase.
Overlaps between static objects will not be detected. All static objects
should have the same group.
\return Filter group for static objects.
\see PxBpFilterGroup
*/
PX_C_EXPORT PX_PHYSX_CORE_API PxBpFilterGroup PxGetBroadPhaseStaticFilterGroup();
/**
\brief Retrieves a filter group for dynamic objects.
Mark dynamic objects with this group when adding them to the broadphase.
Each dynamic object must have an ID, and overlaps between dynamic objects that have
the same ID will not be detected. This is useful to dismiss overlaps between shapes
of the same (compound) actor directly within the broadphase.
\param id [in] ID/Index of dynamic object
\return Filter group for the object.
\see PxBpFilterGroup
*/
PX_C_EXPORT PX_PHYSX_CORE_API PxBpFilterGroup PxGetBroadPhaseDynamicFilterGroup(PxU32 id);
/**
\brief Retrieves a filter group for kinematic objects.
Mark kinematic objects with this group when adding them to the broadphase.
Each kinematic object must have an ID, and overlaps between kinematic objects that have
the same ID will not be detected.
\param id [in] ID/Index of kinematic object
\return Filter group for the object.
\see PxBpFilterGroup
*/
PX_C_EXPORT PX_PHYSX_CORE_API PxBpFilterGroup PxGetBroadPhaseKinematicFilterGroup(PxU32 id);
/**
\brief Broadphase data update structure.
This structure is used to update the low-level broadphase (PxBroadPhase). All added, updated and removed objects
must be batched and submitted at once to the broadphase.
Broadphase objects have bounds, a filtering group, and a distance. With the low-level broadphase the data must be
externally managed by the clients of the broadphase API, and passed to the update function.
The provided bounds are non-inflated "base" bounds that can be further extended by the broadphase using the passed
distance value. These can be contact offsets, or dynamically updated distance values for e.g. speculative contacts.
Either way they are optional and can be left to zero. The broadphase implementations efficiently combine the base
bounds with the per-object distance values at runtime.
The per-object filtering groups are used to discard some pairs directly within the broadphase, which is more
efficient than reporting the pairs and culling them in a second pass.
\see PxBpFilterGroup PxBpIndex PxBounds3 PxBroadPhase::update
*/
class PxBroadPhaseUpdateData
{
public:
PxBroadPhaseUpdateData( const PxBpIndex* created, PxU32 nbCreated,
const PxBpIndex* updated, PxU32 nbUpdated,
const PxBpIndex* removed, PxU32 nbRemoved,
const PxBounds3* bounds, const PxBpFilterGroup* groups, const float* distances,
PxU32 capacity) :
mCreated (created), mNbCreated (nbCreated),
mUpdated (updated), mNbUpdated (nbUpdated),
mRemoved (removed), mNbRemoved (nbRemoved),
mBounds (bounds), mGroups (groups), mDistances (distances),
mCapacity (capacity)
{
}
PxBroadPhaseUpdateData(const PxBroadPhaseUpdateData& other) :
mCreated (other.mCreated), mNbCreated (other.mNbCreated),
mUpdated (other.mUpdated), mNbUpdated (other.mNbUpdated),
mRemoved (other.mRemoved), mNbRemoved (other.mNbRemoved),
mBounds (other.mBounds), mGroups (other.mGroups), mDistances (other.mDistances),
mCapacity (other.mCapacity)
{
}
PxBroadPhaseUpdateData& operator=(const PxBroadPhaseUpdateData& other);
const PxBpIndex* mCreated; //!< Indices of created objects.
const PxU32 mNbCreated; //!< Number of created objects.
const PxBpIndex* mUpdated; //!< Indices of updated objects.
const PxU32 mNbUpdated; //!< Number of updated objects.
const PxBpIndex* mRemoved; //!< Indices of removed objects.
const PxU32 mNbRemoved; //!< Number of removed objects.
const PxBounds3* mBounds; //!< (Persistent) array of bounds.
const PxBpFilterGroup* mGroups; //!< (Persistent) array of groups.
const float* mDistances; //!< (Persistent) array of distances.
const PxU32 mCapacity; //!< Capacity of bounds / groups / distance buffers.
};
/**
\brief Broadphase pair.
A pair of indices returned by the broadphase for found or lost pairs.
\see PxBroadPhaseResults
*/
struct PxBroadPhasePair
{
PxBpIndex mID0; //!< Index of first object
PxBpIndex mID1; //!< Index of second object
};
/**
\brief Broadphase results.
Set of found and lost pairs after a broadphase update.
\see PxBroadPhasePair PxBroadPhase::fetchResults PxAABBManager::fetchResults
*/
struct PxBroadPhaseResults
{
PxBroadPhaseResults() : mNbCreatedPairs(0), mCreatedPairs(NULL), mNbDeletedPairs(0), mDeletedPairs(NULL) {}
PxU32 mNbCreatedPairs; //!< Number of new/found/created pairs.
const PxBroadPhasePair* mCreatedPairs; //!< Array of new/found/created pairs.
PxU32 mNbDeletedPairs; //!< Number of lost/deleted pairs.
const PxBroadPhasePair* mDeletedPairs; //!< Array of lost/deleted pairs.
};
/**
\brief Broadphase regions.
An API to manage broadphase regions. Only needed for the MBP broadphase (PxBroadPhaseType::eMBP).
\see PxBroadPhase::getRegions()
*/
class PxBroadPhaseRegions
{
protected:
PxBroadPhaseRegions() {}
virtual ~PxBroadPhaseRegions() {}
public:
/**
\brief Returns number of regions currently registered in the broad-phase.
\return Number of regions
*/
virtual PxU32 getNbRegions() const = 0;
/**
\brief Gets broad-phase regions.
\param userBuffer [out] Returned broad-phase regions
\param bufferSize [in] Size of provided userBuffer.
\param startIndex [in] Index of first desired region, in [0 ; getNbRegions()[
\return Number of written out regions.
\see PxBroadPhaseRegionInfo
*/
virtual PxU32 getRegions(PxBroadPhaseRegionInfo* userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
/**
\brief Adds a new broad-phase region.
The total number of regions is limited to PxBroadPhaseCaps::mMaxNbRegions. If that number is exceeded, the call is ignored.
The newly added region will be automatically populated with already existing objects that touch it, if the
'populateRegion' parameter is set to true. Otherwise the newly added region will be empty, and it will only be
populated with objects when those objects are added to the simulation, or updated if they already exist.
Using 'populateRegion=true' has a cost, so it is best to avoid it if possible. In particular it is more efficient
to create the empty regions first (with populateRegion=false) and then add the objects afterwards (rather than
the opposite).
Objects automatically move from one region to another during their lifetime. The system keeps tracks of what
regions a given object is in. It is legal for an object to be in an arbitrary number of regions. However if an
object leaves all regions, or is created outside of all regions, several things happen:
- collisions get disabled for this object
- the object appears in the getOutOfBoundsObjects() array
If an out-of-bounds object, whose collisions are disabled, re-enters a valid broadphase region, then collisions
are re-enabled for that object.
\param region [in] User-provided region data
\param populateRegion [in] True to automatically populate the newly added region with existing objects touching it
\param bounds [in] User-managed array of bounds
\param distances [in] User-managed array of distances
\return Handle for newly created region, or 0xffffffff in case of failure.
\see PxBroadPhaseRegion getOutOfBoundsObjects()
*/
virtual PxU32 addRegion(const PxBroadPhaseRegion& region, bool populateRegion, const PxBounds3* bounds, const float* distances) = 0;
/**
\brief Removes a broad-phase region.
If the region still contains objects, and if those objects do not overlap any region any more, they are not
automatically removed from the simulation. Instead, the PxBroadPhaseCallback::onObjectOutOfBounds notification
is used for each object. Users are responsible for removing the objects from the simulation if this is the
desired behavior.
If the handle is invalid, or if a valid handle is removed twice, an error message is sent to the error stream.
\param handle [in] Region's handle, as returned by addRegion
\return True if success
*/
virtual bool removeRegion(PxU32 handle) = 0;
/*
\brief Return the number of objects that are not in any region.
*/
virtual PxU32 getNbOutOfBoundsObjects() const = 0;
/*
\brief Return an array of objects that are not in any region.
*/
virtual const PxU32* getOutOfBoundsObjects() const = 0;
};
/**
\brief Low-level broadphase API.
This low-level API only supports batched updates and leaves most of the data management to its clients.
This is useful if you want to use the broadphase with your own memory buffers. Note however that the GPU broadphase
works best with buffers allocated in CUDA memory. The getAllocator() function returns an allocator that is compatible
with the selected broadphase. It is recommended to allocate and deallocate the broadphase data (bounds, groups, distances)
using this allocator.
Important note: it must be safe to load 4 bytes past the end of the provided bounds array.
The high-level broadphase API (PxAABBManager) is an easier-to-use interface that automatically deals with these requirements.
\see PxCreateBroadPhase
*/
class PxBroadPhase
{
protected:
PxBroadPhase() {}
virtual ~PxBroadPhase() {}
public:
/*
\brief Releases the broadphase.
*/
virtual void release() = 0;
/**
\brief Gets the broadphase type.
\return Broadphase type.
\see PxBroadPhaseType::Enum
*/
virtual PxBroadPhaseType::Enum getType() const = 0;
/**
\brief Gets broad-phase caps.
\param caps [out] Broad-phase caps
\see PxBroadPhaseCaps
*/
virtual void getCaps(PxBroadPhaseCaps& caps) const = 0;
/**
\brief Retrieves the regions API if applicable.
For broadphases that do not use explicit user-defined regions, this call returns NULL.
\return Region API, or NULL.
\see PxBroadPhaseRegions
*/
virtual PxBroadPhaseRegions* getRegions() = 0;
/**
\brief Retrieves the broadphase allocator.
User-provided buffers should ideally be allocated with this allocator, for best performance.
This is especially true for the GPU broadphases, whose buffers need to be allocated in CUDA
host memory.
\return The broadphase allocator.
\see PxAllocatorCallback
*/
virtual PxAllocatorCallback* getAllocator() = 0;
/**
\brief Retrieves the profiler's context ID.
\return The context ID.
\see PxBroadPhaseDesc
*/
virtual PxU64 getContextID() const = 0;
/**
\brief Sets a scratch buffer
Some broadphases might take advantage of a scratch buffer to limit runtime allocations.
All broadphases still work without providing a scratch buffer, this is an optional function
that can potentially reduce runtime allocations.
\param scratchBlock [in] The scratch buffer
\param size [in] Size of the scratch buffer in bytes
*/
virtual void setScratchBlock(void* scratchBlock, PxU32 size) = 0;
/**
\brief Updates the broadphase and computes the lists of created/deleted pairs.
The provided update data describes changes to objects since the last broadphase update.
To benefit from potentially multithreaded implementations, it is necessary to provide a continuation
task to the function. It is legal to pass NULL there, but the underlying (CPU) implementations will
then run single-threaded.
\param updateData [in] The update data
\param continuation [in] Continuation task to enable multi-threaded implementations, or NULL.
\see PxBroadPhaseUpdateData PxBaseTask
*/
virtual void update(const PxBroadPhaseUpdateData& updateData, PxBaseTask* continuation=NULL) = 0;
/**
\brief Retrieves the broadphase results after an update.
This should be called once after each update call to retrieve the results of the broadphase. The
results are incremental, i.e. the system only returns new and lost pairs, not all current pairs.
\param results [out] The broadphase results
\see PxBroadPhaseResults
*/
virtual void fetchResults(PxBroadPhaseResults& results) = 0;
/**
\brief Helper for single-threaded updates.
This short helper function performs a single-theaded update and reports the results in a single call.
\param results [out] The broadphase results
\param updateData [in] The update data
\see PxBroadPhaseUpdateData PxBroadPhaseResults
*/
PX_FORCE_INLINE void update(PxBroadPhaseResults& results, const PxBroadPhaseUpdateData& updateData)
{
update(updateData);
fetchResults(results);
}
};
/**
\brief Broadphase factory function.
Use this function to create a new standalone broadphase.
\param desc [in] Broadphase descriptor
\return Newly created broadphase, or NULL
\see PxBroadPhase PxBroadPhaseDesc
*/
PX_C_EXPORT PX_PHYSX_CORE_API PxBroadPhase* PxCreateBroadPhase(const PxBroadPhaseDesc& desc);
/**
\brief High-level broadphase API.
The low-level broadphase API (PxBroadPhase) only supports batched updates and has a few non-trivial
requirements for managing the bounds data.
The high-level broadphase API (PxAABBManager) is an easier-to-use one-object-at-a-time API that
automatically deals with the quirks of the PxBroadPhase data management.
\see PxCreateAABBManager
*/
class PxAABBManager
{
protected:
PxAABBManager() {}
virtual ~PxAABBManager() {}
public:
/*
\brief Releases the AABB manager.
*/
virtual void release() = 0;
/**
\brief Retrieves the underlying broadphase.
\return The managed broadphase.
\see PxBroadPhase
*/
virtual PxBroadPhase& getBroadPhase() = 0;
/**
\brief Retrieves the managed bounds.
This is needed as input parameters to functions like PxBroadPhaseRegions::addRegion.
\return The managed object bounds.
\see PxBounds3
*/
virtual const PxBounds3* getBounds() const = 0;
/**
\brief Retrieves the managed distances.
This is needed as input parameters to functions like PxBroadPhaseRegions::addRegion.
\return The managed object distances.
*/
virtual const float* getDistances() const = 0;
/**
\brief Retrieves the managed filter groups.
\return The managed object groups.
*/
virtual const PxBpFilterGroup* getGroups() const = 0;
/**
\brief Retrieves the managed buffers' capacity.
Bounds, distances and groups buffers have the same capacity.
\return The managed buffers' capacity.
*/
virtual PxU32 getCapacity() const = 0;
/**
\brief Adds an object to the manager.
Objects' indices are externally managed, i.e. they must be provided by users (as opposed to handles
that could be returned by this manager). The design allows users to identify an object by a single ID,
and use the same ID in multiple sub-systems.
\param index [in] The object's index
\param bounds [in] The object's bounds
\param group [in] The object's filter group
\param distance [in] The object's distance (optional)
\see PxBpIndex PxBounds3 PxBpFilterGroup
*/
virtual void addObject(PxBpIndex index, const PxBounds3& bounds, PxBpFilterGroup group, float distance=0.0f) = 0;
/**
\brief Removes an object from the manager.
\param index [in] The object's index
\see PxBpIndex
*/
virtual void removeObject(PxBpIndex index) = 0;
/**
\brief Updates an object in the manager.
This call can update an object's bounds, distance, or both.
It is not possible to update an object's filter group.
\param index [in] The object's index
\param bounds [in] The object's updated bounds, or NULL
\param distance [in] The object's updated distance, or NULL
\see PxBpIndex PxBounds3
*/
virtual void updateObject(PxBpIndex index, const PxBounds3* bounds=NULL, const float* distance=NULL) = 0;
/**
\brief Updates the broadphase and computes the lists of created/deleted pairs.
The data necessary for updating the broadphase is internally computed by the AABB manager.
To benefit from potentially multithreaded implementations, it is necessary to provide a continuation
task to the function. It is legal to pass NULL there, but the underlying (CPU) implementations will
then run single-threaded.
\param continuation [in] Continuation task to enable multi-threaded implementations, or NULL.
\see PxBaseTask
*/
virtual void update(PxBaseTask* continuation=NULL) = 0;
/**
\brief Retrieves the broadphase results after an update.
This should be called once after each update call to retrieve the results of the broadphase. The
results are incremental, i.e. the system only returns new and lost pairs, not all current pairs.
\param results [out] The broadphase results
\see PxBroadPhaseResults
*/
virtual void fetchResults(PxBroadPhaseResults& results) = 0;
/**
\brief Helper for single-threaded updates.
This short helper function performs a single-theaded update and reports the results in a single call.
\param results [out] The broadphase results
\see PxBroadPhaseResults
*/
PX_FORCE_INLINE void update(PxBroadPhaseResults& results)
{
update();
fetchResults(results);
}
};
/**
\brief AABB manager factory function.
Use this function to create a new standalone high-level broadphase.
\param broadphase [in] The broadphase that will be managed by the AABB manager
\return Newly created AABB manager, or NULL
\see PxAABBManager PxBroadPhase
*/
PX_C_EXPORT PX_PHYSX_CORE_API PxAABBManager* PxCreateAABBManager(PxBroadPhase& broadphase);
#if !PX_DOXYGEN
} // namespace physx
#endif

136
Source/ThirdParty/PhysX/PxBuffer.h vendored Normal file
View File

@@ -0,0 +1,136 @@
// 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-2023 NVIDIA Corporation. All rights reserved.
#ifndef PX_BUFFER_H
#define PX_BUFFER_H
/** \addtogroup physics
@{ */
#include "foundation/PxFlags.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
#if PX_VC
#pragma warning(push)
#pragma warning(disable : 4435)
#endif
class PxCudaContextManager;
/**
\brief Specifies memory space for a PxBuffer instance.
@see PxBuffer
*/
struct PxBufferType
{
enum Enum
{
eHOST,
eDEVICE
};
};
/**
\brief Buffer for delayed bulk read and write operations supporting host and GPU device memory spaces.
@see PxPhysics::createBuffer(), PxParticleSystem
*/
class PxBuffer
{
public:
/**
\brief Deletes the buffer.
Do not keep a reference to the deleted instance.
Unfinished operations will be flushed and synchronized on.
*/
virtual void release() = 0;
/**
\brief Provides access to internal memory (either device or pinned host memory depending on PxBufferType).
Unfinished operations will be flushed and synchronized on before returning.
*/
virtual void* map() = 0;
/**
\brief Releases access to internal memory (either device or pinned host memory depending on PxBufferType).
\param[in] event Optional pointer to CUevent. Used to synchronize on application side work that needs to be completed before
buffer can be accessed again.
*/
virtual void unmap(void* event = NULL) = 0;
/**
\brief Buffer memory space type.
@see PxBufferType
*/
virtual PxBufferType::Enum getBufferType() const = 0;
/**
\brief Size of buffer in bytes.
*/
virtual PxU64 getByteSize() const = 0;
/**
\brief Get the associated PxCudaContextManager.
@see PxCudaContextManager.
*/
virtual PxCudaContextManager* getCudaContextManager() const = 0;
/**
\brief Helper function to synchronize on all pending operations.
@see PxCudaContextManager.
*/
PX_INLINE void sync() { map(); unmap(); }
virtual void resize(PxU64 size) = 0;
protected:
virtual ~PxBuffer() {}
PX_INLINE PxBuffer() {}
};
#if PX_VC
#pragma warning(pop)
#endif
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@@ -1,4 +1,3 @@
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
@@ -11,7 +10,7 @@
// 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
// 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
@@ -23,13 +22,12 @@
// (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-2019 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2008-2023 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_PHYSICS_NX_CLIENT
#define PX_PHYSICS_NX_CLIENT
#ifndef PX_CLIENT_H
#define PX_CLIENT_H
#include "foundation/PxFlags.h"
@@ -52,13 +50,6 @@ typedef PxU8 PxClientID;
*/
static const PxClientID PX_DEFAULT_CLIENT = 0;
/**
\brief The maximum number of clients we support.
@see PxClientID PxScene::createClient()
*/
static const PxClientID PX_MAX_CLIENTS = 128;
#if !PX_DOXYGEN
} // namespace physx
#endif

Some files were not shown because too many files have changed in this diff Show More