branch with experimental PyBullet support for PhysX

see otherPhysicsEngine in examples/pybullet/examples folder for example usage
This commit is contained in:
Erwin Coumans 2019-02-13 14:57:11 -08:00
parent a38093ad61
commit f6f9de12af
1363 changed files with 413562 additions and 484 deletions

1160
setup.py

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,330 @@
//
// 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-2018 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
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "foundation/PxBounds3.h"
#include "PxClient.h"
#include "common/PxBase.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxRigidActor;
class PxRigidBody;
class PxRigidStatic;
class PxRigidDynamic;
class PxArticulation;
class PxArticulationLink;
/** Group index which allows to specify 1- or 2-way interaction */
typedef PxU8 PxDominanceGroup; // Must be < 32, PxU8.
/**
\brief Flags which control the behavior of an actor.
@see PxActorFlags PxActor PxActor.setActorFlag() PxActor.getActorFlags()
*/
struct PxActorFlag
{
enum Enum
{
/**
\brief Enable debug renderer for this actor
@see PxScene.getRenderBuffer() PxRenderBuffer PxVisualizationParameter
*/
eVISUALIZATION = (1<<0),
/**
\brief Disables scene gravity for this actor
*/
eDISABLE_GRAVITY = (1<<1),
/**
\brief Enables the sending of PxSimulationEventCallback::onWake() and PxSimulationEventCallback::onSleep() notify events
@see PxSimulationEventCallback::onWake() PxSimulationEventCallback::onSleep()
*/
eSEND_SLEEP_NOTIFIES = (1<<2),
/**
\brief Disables simulation for the actor.
\note This is only supported by PxRigidStatic and PxRigidDynamic actors and can be used to reduce the memory footprint when rigid actors are
used for scene queries only.
\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 PxRigidDynamic: setKinematicTarget(), setWakeCounter(), wakeUp(), putToSleep()
\par <b>Sleeping:</b>
Raising this flag will set all velocities and the wake counter to 0, clear all forces, clear the kinematic target, put the actor
to sleep and wake up all touching actors from the previous frame.
*/
eDISABLE_SIMULATION = (1<<3)
};
};
/**
\brief collection of set bits defined in PxActorFlag.
@see PxActorFlag
*/
typedef PxFlags<PxActorFlag::Enum,PxU8> PxActorFlags;
PX_FLAGS_OPERATORS(PxActorFlag::Enum,PxU8)
/**
\brief Identifies each type of actor.
@see PxActor
*/
struct PxActorType
{
enum Enum
{
/**
\brief A static rigid body
@see PxRigidStatic
*/
eRIGID_STATIC,
/**
\brief A dynamic rigid body
@see PxRigidDynamic
*/
eRIGID_DYNAMIC,
/**
\brief An articulation link
@see PxArticulationLink
*/
eARTICULATION_LINK,
//brief internal use only!
eACTOR_COUNT,
eACTOR_FORCE_DWORD = 0x7fffffff
};
};
/**
\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
{
public:
/**
\brief Deletes the actor.
Do not keep a reference to the deleted instance.
If the actor belongs to a #PxAggregate object, it is automatically removed from the aggregate.
@see PxBase.release(), PxAggregate
*/
virtual void release() = 0;
/**
\brief Retrieves the type of actor.
\return The actor type of the actor.
@see PxActorType
*/
virtual PxActorType::Enum getType() const = 0;
/**
\brief Retrieves the scene which this actor belongs to.
\return Owner Scene. NULL if not part of a scene.
@see PxScene
*/
virtual PxScene* getScene() const = 0;
// Runtime modifications
/**
\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.
<b>Default:</b> NULL
@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 actor.
\param[in] inflation Scale factor for computed world bounds. Box extents are multiplied by this value.
\return The actor's bounding box.
@see PxBounds3
*/
virtual PxBounds3 getWorldBounds(float inflation=1.01f) const = 0;
/**
\brief Raises or clears a particular actor flag.
See the list of flags #PxActorFlag
<b>Sleeping:</b> Does <b>NOT</b> wake the actor up automatically.
\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
See the list of flags #PxActorFlag
@see PxActorFlag setActorFlag()
*/
virtual void setActorFlags( PxActorFlags inFlags ) = 0;
/**
\brief Reads the PxActor flags.
See the list of flags #PxActorFlag
\return The values of the PxActor flags.
@see PxActorFlag setActorFlag()
*/
virtual PxActorFlags getActorFlags() const = 0;
/**
\brief Assigns dynamic actors a dominance group identifier.
PxDominanceGroup is a 5 bit group identifier (legal range from 0 to 31).
The PxScene::setDominanceGroupPair() lets you set certain behaviors for pairs of dominance groups.
By default every dynamic actor is created in group 0.
<b>Default:</b> 0
<b>Sleeping:</b> Changing the dominance group does <b>NOT</b> wake the actor up automatically.
\param[in] dominanceGroup The dominance group identifier. <b>Range:</b> [0..31]
@see getDominanceGroup() PxDominanceGroup PxScene::setDominanceGroupPair()
*/
virtual void setDominanceGroup(PxDominanceGroup dominanceGroup) = 0;
/**
\brief Retrieves the value set with setDominanceGroup().
\return The dominance group of this actor.
@see setDominanceGroup() PxDominanceGroup PxScene::setDominanceGroupPair()
*/
virtual PxDominanceGroup getDominanceGroup() const = 0;
/**
\brief Sets the owner client of an actor.
This cannot be done once the actor has been placed into a scene.
<b>Default:</b> PX_DEFAULT_CLIENT
@see PxClientID PxScene::createClient()
*/
virtual void setOwnerClient( PxClientID inClient ) = 0;
/**
\brief Returns the owner client that was specified with at creation time.
This value cannot be changed once the object is placed into the scene.
@see PxClientID PxScene::createClient()
*/
virtual PxClientID getOwnerClient() const = 0;
/**
\brief Retrieves the aggregate the actor might be a part of.
\return The aggregate the actor is a part of, or NULL if the actor does not belong to an aggregate.
@see PxAggregate
*/
virtual PxAggregate* getAggregate() const = 0;
//public variables:
void* userData; //!< user can assign this to whatever, usually to create a 1:1 relationship with a user object.
protected:
PX_INLINE PxActor(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags), userData(NULL) {}
PX_INLINE PxActor(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
virtual ~PxActor() {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxActor", name) || PxBase::isKindOf(name); }
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,213 @@
//
// 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-2018 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
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "common/PxBase.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxActor;
class PxBVHStructure;
/**
\brief Class to aggregate actors into a single broad-phase entry.
A PxAggregate object is a collection of PxActors, which will exist as a single entry in the
broad-phase structures. This has 3 main benefits:
1) it reduces "broad phase pollution" by allowing a collection of spatially coherent broad-phase
entries to be replaced by a single aggregated entry (e.g. a ragdoll or a single actor with a
large number of attached shapes).
2) it reduces broad-phase memory usage
3) filtering can be optimized a lot if self-collisions within an aggregate are not needed. For
example if you don't need collisions between ragdoll bones, it's faster to simply disable
filtering once and for all, for the aggregate containing the ragdoll, rather than filtering
out each bone-bone collision in the filter shader.
@see PxActor, PxPhysics.createAggregate
*/
class PxAggregate : public PxBase
{
public:
/**
\brief Deletes the aggregate object.
Deleting the PxAggregate object does not delete the aggregated actors. If the PxAggregate object
belongs to a scene, the aggregated actors are automatically re-inserted in that scene. If you intend
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;
/**
\brief Adds an actor to the aggregate object.
A warning is output if the total number of actors is reached, or if the incoming actor already belongs
to an aggregate.
If the aggregate belongs to a scene, adding an actor to the aggregate also adds the actor to that scene.
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.
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.
\param [in] actor The actor that should be added to the aggregate
\param [in] bvhStructure BVHStructure for actor shapes.
return true if success
*/
virtual bool addActor(PxActor& actor, const PxBVHStructure* bvhStructure = NULL) = 0;
/**
\brief Removes an actor from the aggregate object.
A warning is output if the incoming actor does not belong to the aggregate. Otherwise the actor is
removed from the aggregate. If the aggregate belongs to a scene, the actor is reinserted in that
scene. If you intend to delete the actor, it is best to call #PxActor::release() directly. That way
the actor will be automatically removed from its aggregate (if any) and not reinserted in a scene.
\param [in] actor The actor that should be removed from the aggregate
return true if success
*/
virtual bool removeActor(PxActor& actor) = 0;
/**
\brief Adds an articulation to the aggregate object.
A warning is output if the total number of actors is reached (every articulation link counts as an actor),
or if the incoming articulation already belongs to an aggregate.
If the aggregate belongs to a scene, adding an articulation to the aggregate also adds the articulation to that scene.
If the articulation already belongs to a scene, a warning is output and the call is ignored. You need to remove
the articulation from the scene first, before adding it to the aggregate.
\param [in] articulation The articulation that should be added to the aggregate
return true if success
*/
virtual bool addArticulation(PxArticulationBase& 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
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;
/**
\brief Returns the number of actors contained in the aggregate.
You can use #getActors() to retrieve the actor pointers.
\return Number of actors contained in the aggregate.
@see PxActor getActors()
*/
virtual PxU32 getNbActors() const = 0;
/**
\brief Retrieves max amount of actors that can be contained in the aggregate.
\return Max aggregate size.
@see PxPhysics::createAggregate()
*/
virtual PxU32 getMaxNbActors() const = 0;
/**
\brief Retrieve all actors contained in the aggregate.
You can retrieve the number of actor pointers by calling #getNbActors()
\param[out] userBuffer The buffer to store the actor pointers.
\param[in] bufferSize Size of provided user buffer.
\param[in] startIndex Index of first actor pointer to be retrieved
\return Number of actor pointers written to the buffer.
@see PxShape getNbShapes()
*/
virtual PxU32 getActors(PxActor** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
/**
\brief Retrieves the scene which this aggregate belongs to.
\return Owner Scene. NULL if not part of a scene.
@see PxScene
*/
virtual PxScene* getScene() = 0;
/**
\brief Retrieves aggregate's self-collision flag.
\return self-collision flag
*/
virtual bool getSelfCollision() const = 0;
virtual const char* getConcreteTypeName() const { return "PxAggregate"; }
protected:
PX_INLINE PxAggregate(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags) {}
PX_INLINE PxAggregate(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
virtual ~PxAggregate() {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxAggregate", name) || PxBase::isKindOf(name); }
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,281 @@
//
// 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-2018 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

@ -0,0 +1,337 @@
//
// 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-2018 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:
enum Enum
{
eReducedCoordinate = 0,
eMaximumCoordinate = 1
};
/**
\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;
virtual PxArticulationBase::Enum getType() 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) {}
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,572 @@
//
// 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-2018 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"
#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.
};
};
struct PxArticulationAxis
{
enum Enum
{
eTWIST = 0,
eSWING1 = 1,
eSWING2 = 2,
eX = 3,
eY = 4,
eZ = 5,
eCOUNT = 6
};
};
PX_FLAGS_OPERATORS(PxArticulationAxis::Enum, PxU8)
struct PxArticulationMotion
{
enum Enum
{
eLOCKED = 0,
eLIMITED = 1,
eFREE = 2
};
};
typedef PxFlags<PxArticulationMotion::Enum, PxU8> PxArticulationMotions;
PX_FLAGS_OPERATORS(PxArticulationMotion::Enum, PxU8)
struct PxArticulationJointType
{
enum Enum
{
ePRISMATIC = 0,
eREVOLUTE = 1,
eSPHERICAL = 2,
eFIX = 3,
eUNDEFINED = 4
};
};
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

@ -0,0 +1,95 @@
//
// 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-2018 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
/** \addtogroup physics
@{ */
#if 1
#include "PxPhysXConfig.h"
#include "common/PxBase.h"
#include "PxArticulationJoint.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\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 PxArticulationJointReducedCoordinate : public PxArticulationJointBase
{
public:
virtual void setJointType(PxArticulationJointType::Enum jointType) = 0;
virtual PxArticulationJointType::Enum getJointType() const = 0;
virtual void setMotion(PxArticulationAxis::Enum axis, PxArticulationMotion::Enum motion) = 0;
virtual PxArticulationMotion::Enum getMotion(PxArticulationAxis::Enum axis) 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, bool isAccelerationDrive = false) = 0;
virtual void getDrive(PxArticulationAxis::Enum axis, PxReal& stiffness, PxReal& damping, PxReal& maxForce, bool& isAcceleration) = 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;
virtual void setFrictionCoefficient(const PxReal coefficient) = 0;
virtual PxReal getFrictionCoefficient() const = 0;
virtual const char* getConcreteTypeName() const { return "PxArticulationJointReducedCoordinate"; }
virtual void setMaxJointVelocity(const PxReal maxJointV) = 0;
virtual PxReal getMaxJointVelocity() const = 0;
protected:
PX_INLINE PxArticulationJointReducedCoordinate(PxType concreteType, PxBaseFlags baseFlags) : PxArticulationJointBase(concreteType, baseFlags) {}
PX_INLINE PxArticulationJointReducedCoordinate(PxBaseFlags baseFlags) : PxArticulationJointBase(baseFlags) {}
virtual ~PxArticulationJointReducedCoordinate() {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxArticulationJointReducedCoordinate", name) || PxBase::isKindOf(name); }
};
#if !PX_DOXYGEN
} // namespace physx
#endif
#endif
/** @} */
#endif

View File

@ -0,0 +1,142 @@
//
// 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-2018 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
/** \addtogroup physics
@{ */
#include "PxPhysXConfig.h"
#include "PxArticulationJoint.h"
#include "PxRigidBody.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxArticulationBase;
/**
\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.
@see PxArticulation PxArticulation.createLink PxArticulationJoint PxRigidBody
*/
class PxArticulationLink : public PxRigidBody
{
public:
/**
\brief Deletes the articulation link.
\note Only a leaf articulation link can be released
Do not keep a reference to the deleted instance.
@see PxArticulation::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
\return the articulation to which this link belongs
*/
virtual PxArticulationBase& getArticulation() const = 0;
/**
\brief Get 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
*/
virtual PxArticulationJointBase* getInboundJoint() const = 0;
/**
\brief Get the degree 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.
@see PxArticulationJoint
*/
virtual PxU32 getInboundJointDof() const = 0;
/**
\brief Get number of child links.
\return the number of child links
@see getChildren()
*/
virtual PxU32 getNbChildren() const = 0;
/**
\brief Get low-level link index
\return low-level index
*/
virtual PxU32 getLinkIndex() const = 0;
/**
\brief Retrieve all 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
@see getNbChildren()
*/
virtual PxU32 getChildren(PxArticulationLink** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
virtual const char* getConcreteTypeName() const { return "PxArticulationLink"; }
protected:
PX_INLINE PxArticulationLink(PxType concreteType, PxBaseFlags baseFlags) : PxRigidBody(concreteType, baseFlags) {}
PX_INLINE PxArticulationLink(PxBaseFlags baseFlags) : PxRigidBody(baseFlags) {}
virtual ~PxArticulationLink() {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxArticulationLink", name) || PxRigidBody::isKindOf(name); }
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,409 @@
//
// 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-2018 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_RC
#define PX_PHYSICS_NX_ARTICULATION_RC
/** \addtogroup physics
@{ */
#include "PxArticulationBase.h"
#include "foundation/PxVec3.h"
#include "foundation/PxTransform.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
namespace Cm
{
class SpatialVector;
}
class PxContactJoint;
struct PxArticulationFlag
{
enum Enum
{
eFIX_BASE = (1 << 1)
};
};
class PxJoint;
typedef PxFlags<PxArticulationFlag::Enum, PxU8> PxArticulationFlags;
PX_FLAGS_OPERATORS(PxArticulationFlag::Enum, PxU8)
//PxKinematicJacobian is in world space 6x6 matrix
class PxKinematicJacobian
{
public:
//in each single column, top part is angular term and bottom is linear term
PxReal j[6][6];//[column][row]
PxU32 nbColumns;
};
struct PxArticulationRootLinkData
{
PxTransform transform;
PxVec3 linVel;
PxVec3 angVel;
PxVec3 linAcel;
PxVec3 angAcel;
};
class PxArticulationCache
{
public:
enum Enum
{
eVELOCITY = (1 << 0), //!< The joint velocities this frame. Note, this is the accumulated joint velocities, not change in joint velocity.
eACCELERATION = (1 << 1), //!< The joint accelerations this frame. Delta velocity can be computed from acceleration * dt.
ePOSITION = (1 << 2), //!< The joint positions this frame. Note, this is the accumulated joint positions over frames, not change in joint position.
eFORCE = (1 << 3), //!< The joint forces this frame. Note, the application should provide these values for the forward dynamic. If the application is using inverse dynamic, this is the joint force returned.
eROOT = (1 << 4), //!< Root link transform, velocity and acceleration. Note, when the application call applyCache with eROOT flag, it won't apply root link's acceleration to the simulation
eALL = (eVELOCITY | eACCELERATION | ePOSITION| eROOT)
};
PxArticulationCache() : coefficentMatrix(NULL), lambda(NULL)
{}
Cm::SpatialVector* externalForces; // N total number of links
PxKinematicJacobian* jacobian; //this store jacobian matrix
PxReal* massMatrix; //N X N (dof X dof)
PxReal* jointVelocity; //N total Dofs
PxReal* jointAcceleration; //N total Dofs
PxReal* jointPosition; //N total Dofs
PxReal* jointForce; //N total Dofs
//application need to allocate those memory and assign them to the cache
PxReal* coefficentMatrix;
PxReal* lambda;
//root link data
PxArticulationRootLinkData rootLinkData;
//These three members won't be set to zero when zeroCache get called
void* scratchMemory; //this is used for internal calculation
void* scratchAllocator;
PxU32 version; //cache version. If the articulation configulation change, the cache is invalid
};
typedef PxFlags<PxArticulationCache::Enum, PxU8> PxArticulationCacheFlags;
PX_FLAGS_OPERATORS(PxArticulationCache::Enum, PxU8)
/**
\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 PxArticulationReducedCoordinate : public PxArticulationBase
{
public:
virtual void release() = 0;
/**
\brief Sets flags on the articulation
\param[in] flags Articulation flags
*/
virtual void setArticulationFlags(PxArticulationFlags flags) = 0;
/**
\brief Raises or clears a flag on the articulation
\param[in] flag The articulation flag
\param[in] value true/false indicating whether to raise or clear the flag
*/
virtual void setArticulationFlag(PxArticulationFlag::Enum flag, bool value) = 0;
/**
\brief return PxArticulationFlags
*/
virtual PxArticulationFlags getArticulationFlags() const = 0;
/**
\brief returns the total Dofs of the articulation
*/
virtual PxU32 getDofs() const = 0;
/**
\brief create an articulation cache
\note this call may only be made on articulations that are in a scene, and may not be made during simulation
*/
virtual PxArticulationCache* createCache() const = 0;
/**
\brief Get the size of the articulation cache
\note this call may only be made on articulations that are in a scene, and may not be made during simulation
*/
virtual PxU32 getCacheDataSize() const = 0;
/**
\brief zero all data in the articulation cache beside the cache version
\note this call may only be made on articulations that are in a scene, and may not be made during simulation
*/
virtual void zeroCache(PxArticulationCache& cache) = 0;
/**
\brief apply the user defined data in the cache to the articulation system
\param[in] cache articulation data.
\param[in] flag The mode to use when determine which value in the cache will be applied to the articulation
\param[in] autowake Specify if the call should wake up the articulation if it is currently asleep. If true and the current wake counter value is smaller than #PxSceneDesc::wakeCounterResetValue it will get increased to the reset value.
@see createCache copyInternalStateToCache
*/
virtual void applyCache(PxArticulationCache& cache, const PxArticulationCacheFlags flag, bool autowake = true) = 0;
/**
\brief copy the internal data of the articulation to the cache
\param[in] cache articulation data
\param[in] flag this indicates what kind of data the articulation system need to copy to the cache
@see createCache applyCache
*/
virtual void copyInternalStateToCache(PxArticulationCache& cache, const PxArticulationCacheFlags flag) const = 0;
/**
\brief release an articulation cache
\param[in] cache the cache to release
@see createCache applyCache copyInternalStateToCache
*/
virtual void releaseCache(PxArticulationCache& cache) const = 0;
/**
\brief reduce the maximum data format to the reduced internal data
\param[in] maximum joint data format
\param[out] reduced joint data format
*/
virtual void packJointData(const PxReal* maximum, PxReal* reduced) const = 0;
/**
\brief turn the reduced internal data to maximum joint data format
\param[in] reduced joint data format
\param[out] maximum joint data format
*/
virtual void unpackJointData(const PxReal* reduced, PxReal* maximum) const = 0;
/**
\brief initialize all the common data for inverse dynamic
*/
virtual void commonInit() const = 0;
/**
\brief determine the statically balance of the joint force of gravity for entire articulation. External force, joint velocity and joint acceleration
are set to zero, the joint force returned will be purely determined by gravity.
\param[out] cache return joint forces which can counteract gravity force
@see commonInit
*/
virtual void computeGeneralizedGravityForce(PxArticulationCache& cache) const = 0;
/**
\brief determine coriolise and centrifugal force. External force, gravity and joint acceleration
are set to zero, the joint force return will be coriolise and centrifugal force for each joint.
\param[in] cache data
@see commonInit
*/
virtual void computeCoriolisAndCentrifugalForce(PxArticulationCache& cache) const = 0;
/**
\brief determine joint force change caused by external force. Gravity, joint acceleration and joint velocity
are all set to zero.
\param[in] cache data
@see commonInit
*/
virtual void computeGeneralizedExternalForce(PxArticulationCache& cache) const = 0;
/**
\brief determine the joint acceleration for each joint
This is purely calculates the change in joint acceleration due to change in the joint force
\param[in] cache articulation data
@see commonInit
*/
virtual void computeJointAcceleration(PxArticulationCache& cache) const = 0;
/**
\brief determine the joint force
This is purely calculates the change in joint force due to change in the joint acceleration
This means gravity and joint velocity will be zero
\param[in] cache return joint force
@see commonInit
*/
virtual void computeJointForce(PxArticulationCache& cache) const = 0;
/**
\brief compute the kinematic jacobian for each joint from end effector to the root in world space
\param[in] linkID is the end effector id
\param[in] cache return jacobian matrix
@see commonInit
*/
virtual void computeKinematicJacobian(const PxU32 linkID, PxArticulationCache& cache) const = 0;
/**
\brief compute the coefficent matrix for contact force. PxContactJoint is the contact point
\param[out] cache returs the coefficent matrix. Each column is the joint force effected by a contact based on impulse strength 1
@see commonInit
*/
virtual void computeCoefficentMatrix(PxArticulationCache& cache) const = 0;
/**
\brief compute the lambda value when the test impulse is 1
\param[in] initialState the initial state of the articulation system
\param[in] jointTorque M(q)*qddot + C(q,qdot) + g(q)
\param[in] maxIter maximum number of solver iterations to run. If the system converges, fewer iterations may be used.
\param[out] cache returns the coefficent matrix. Each column is the joint force effected by a contact based on impulse strength 1
@see commonInit
*/
virtual bool computeLambda(PxArticulationCache& cache, PxArticulationCache& initialState, const PxReal* const jointTorque, const PxU32 maxIter) const = 0;
/**
\brief compute the joint-space inertia matrix
\param[in] cache articulation data
@see commonInit
*/
virtual void computeGeneralizedMassMatrix(PxArticulationCache& cache) const = 0;
/**
\brief add loop joint to the articulation system for inverse dynamic
\param[in] joint required to add loop joint
@see commonInit
*/
virtual void addLoopJoint(PxJoint* joint) = 0;
/**
\brief remove loop joint from the articulation system
\param[in] joint required to remove loop joint
@see commonInit
*/
virtual void removeLoopJoint(PxJoint* joint) = 0;
/**
\brief returns the number of loop joints in the articulation
\return number of loop joints
*/
virtual PxU32 getNbLoopJoints() const = 0;
/**
\brief returns the set of loop constraints in the articulation
\param[in] userBuffer buffer into which to write an array of constraints 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 getLoopJoints(PxJoint** userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0;
/**
\brief returns the required size of coeffient matrix in the articulation. The coefficient matrix is number of constraint(loop joints) by total dofs. Constraint Torque = transpose(K) * lambda(). Lambda is a vector of number of constraints
\return bite size of the coefficient matrix(nc * n)
*/
virtual PxU32 getCoefficentMatrixSize() const = 0;
/**
\brief teleport root link to a new location
\param[in] pose the new location of the root link
\param[in] autowake wake up the articulation system
@see commonInit
*/
virtual void teleportRootLink(const PxTransform& pose, bool autowake) = 0;
protected:
PX_INLINE PxArticulationReducedCoordinate(PxType concreteType, PxBaseFlags baseFlags) : PxArticulationBase(concreteType, baseFlags) {}
PX_INLINE PxArticulationReducedCoordinate(PxBaseFlags baseFlags) : PxArticulationBase(baseFlags) {}
virtual ~PxArticulationReducedCoordinate() {}
};
#if PX_VC
#pragma warning(pop)
#endif
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,224 @@
//
// 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-2018 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 filer 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

@ -0,0 +1,303 @@
//
// 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-2018 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

@ -0,0 +1,174 @@
//
// 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-2018 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
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "foundation/PxBounds3.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxActor;
/**
\brief Broad phase algorithm used in the simulation
eSAP is a good generic choice with great performance when many objects are sleeping. Performance
can degrade significantly though, when all objects are moving, or when large numbers of objects
are added to or removed from the broad phase. This algorithm does not need world bounds to be
defined in order to work.
eMBP is an alternative broad phase algorithm that does not suffer from the same performance
issues as eSAP when all objects are moving or when inserting large numbers of objects. However
its generic performance when many objects are sleeping might be inferior to eSAP, and it requires
users to define world bounds in order to work.
eABP is a revisited implementation of MBP, which automatically manages broad-phase regions.
It offers the convenience of eSAP (no need to define world bounds or regions) and the performance
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.
*/
struct PxBroadPhaseType
{
enum Enum
{
eSAP, //!< 3-axes sweep-and-prune
eMBP, //!< Multi box pruning
eABP, //!< Automatic box pruning
eGPU,
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.
This is currently only used for the PxBroadPhaseType::eMBP broad-phase, which requires zones or regions to be defined
when the simulation starts in order to work. Regions can overlap and be added or removed at runtime, but at least one
region needs to be defined when the scene is created.
If objects that do no overlap any region are inserted into the scene, they will not be added to the broad-phase and
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 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
around the whole world, and subdivide these bounds into 4*4 regions. The PxBroadPhaseExt::createRegionsFromWorldBounds
function can do that for you.
@see PxBroadPhaseCallback PxBroadPhaseExt.createRegionsFromWorldBounds
*/
struct PxBroadPhaseRegion
{
PxBounds3 bounds; //!< Region's bounds
void* userData; //!< Region's user-provided data
};
/**
\brief Information & stats structure for a region
*/
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)
};
/**
\brief Caps class for broad phase.
*/
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
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,66 @@
//
// 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-2018 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
#include "foundation/PxFlags.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief An ID to identify different clients for multiclient support.
@see PxScene::createClient()
*/
typedef PxU8 PxClientID;
/**
\brief The predefined default PxClientID value.
@see PxClientID PxScene::createClient()
*/
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
#endif

View File

@ -0,0 +1,280 @@
//
// 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-2018 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_CONSTRAINT
#define PX_PHYSICS_NX_CONSTRAINT
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "PxConstraintDesc.h"
#include "common/PxBase.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxRigidActor;
class PxScene;
class PxConstraintConnector;
/**
\brief a table of function pointers for a constraint
@see PxConstraint
*/
/**
\brief constraint flags
\note eBROKEN is a read only flag
*/
struct PxConstraintFlag
{
enum Enum
{
eBROKEN = 1<<0, //!< whether the constraint is broken
ePROJECT_TO_ACTOR0 = 1<<1, //!< whether actor1 should get projected to actor0 for this constraint (note: projection of a static/kinematic actor to a dynamic actor will be ignored)
ePROJECT_TO_ACTOR1 = 1<<2, //!< whether actor0 should get projected to actor1 for this constraint (note: projection of a static/kinematic actor to a dynamic actor will be ignored)
ePROJECTION = ePROJECT_TO_ACTOR0 | ePROJECT_TO_ACTOR1, //!< whether the actors should get projected for this constraint (the direction will be chosen by PhysX)
eCOLLISION_ENABLED = 1<<3, //!< whether contacts should be generated between the objects this constraint constrains
eVISUALIZATION = 1<<4, //!< whether this constraint should be visualized, if constraint visualization is turned on
eDRIVE_LIMITS_ARE_FORCES = 1<<5, //!< limits for drive strength are forces rather than impulses
eIMPROVED_SLERP = 1<<7, //!< perform preprocessing for improved accuracy on D6 Slerp Drive (this flag will be removed in a future release when preprocessing is no longer required)
eDISABLE_PREPROCESSING = 1<<8, //!< suppress constraint preprocessing, intended for use with rowResponseThreshold. May result in worse solver accuracy for ill-conditioned constraints.
eENABLE_EXTENDED_LIMITS = 1<<9, //!< enables extended limit ranges for angular limits (e.g. limit values > PxPi or < -PxPi)
eGPU_COMPATIBLE = 1<<10 //!< the constraint type is supported by gpu dynamic
};
};
/**
\brief constraint flags
@see PxConstraintFlag
*/
typedef PxFlags<PxConstraintFlag::Enum, PxU16> PxConstraintFlags;
PX_FLAGS_OPERATORS(PxConstraintFlag::Enum, PxU16)
struct PxConstraintShaderTable
{
enum
{
eMAX_SOLVERPRPEP_DATASIZE=400
};
PxConstraintSolverPrep solverPrep; //!< solver constraint generation function
PxConstraintProject project; //!< constraint projection function
PxConstraintVisualize visualize; //!< constraint visualization function
PxConstraintFlag::Enum flag; //!< gpu constraint
};
/**
\brief A plugin class for implementing constraints
@see PxPhysics.createConstraint
*/
class PxConstraint : public PxBase
{
public:
/**
\brief Releases a PxConstraint instance.
\note This call does not wake up the connected rigid bodies.
@see PxPhysics.createConstraint, PxBase.release()
*/
virtual void release() = 0;
/**
\brief Retrieves the scene which this constraint belongs to.
\return Owner Scene. NULL if not part of a scene.
@see PxScene
*/
virtual PxScene* getScene() const = 0;
/**
\brief Retrieves the actors for this constraint.
\param[out] actor0 a reference to the pointer for the first actor
\param[out] actor1 a reference to the pointer for the second actor
@see PxActor
*/
virtual void getActors(PxRigidActor*& actor0, PxRigidActor*& actor1) const = 0;
/**
\brief Sets the actors for this constraint.
\param[in] actor0 a reference to the pointer for the first actor
\param[in] actor1 a reference to the pointer for the second actor
@see PxActor
*/
virtual void setActors(PxRigidActor* actor0, PxRigidActor* actor1) = 0;
/**
\brief Notify the scene that the constraint shader data has been updated by the application
*/
virtual void markDirty() = 0;
/**
\brief Set the flags for this constraint
\param[in] flags the new constraint flags
default: PxConstraintFlag::eDRIVE_LIMITS_ARE_FORCES
@see PxConstraintFlags
*/
virtual void setFlags(PxConstraintFlags flags) = 0;
/**
\brief Retrieve the flags for this constraint
\return the constraint flags
@see PxConstraintFlags
*/
virtual PxConstraintFlags getFlags() const = 0;
/**
\brief Set a flag for this constraint
\param[in] flag the constraint flag
\param[in] value the new value of the flag
@see PxConstraintFlags
*/
virtual void setFlag(PxConstraintFlag::Enum flag, bool value) = 0;
/**
\brief Retrieve the constraint force most recently applied to maintain this constraint.
\param[out] linear the constraint force
\param[out] angular the constraint torque
*/
virtual void getForce(PxVec3& linear, PxVec3& angular) const = 0;
/**
\brief whether the constraint is valid.
A constraint is valid if it has at least one dynamic rigid body or articulation link. A constraint that
is not valid may not be inserted into a scene, and therefore a static actor to which an invalid constraint
is attached may not be inserted into a scene.
Invalid constraints arise only when an actor to which the constraint is attached has been deleted.
*/
virtual bool isValid() const = 0;
/**
\brief Set the break force and torque thresholds for this constraint.
If either the force or torque measured at the constraint exceed these thresholds the constraint will break.
\param[in] linear the linear break threshold
\param[in] angular the angular break threshold
*/
virtual void setBreakForce(PxReal linear, PxReal angular) = 0;
/**
\brief Retrieve the constraint break force and torque thresholds
\param[out] linear the linear break threshold
\param[out] angular the angular break threshold
*/
virtual void getBreakForce(PxReal& linear, PxReal& angular) const = 0;
/**
\brief Set the minimum response threshold for a constraint row
When using mass modification for a joint or infinite inertia for a jointed body, very stiff solver constraints can be generated which
can destabilize simulation. Setting this value to a small positive value (e.g. 1e-8) will cause constraint rows to be ignored if very
large changes in impulses will generate only small changes in velocity. When setting this value, also set
PxConstraintFlag::eDISABLE_PREPROCESSING. The solver accuracy for this joint may be reduced.
\param[in] threshold the minimum response threshold
@see PxConstraintFlag::eDISABLE_PREPROCESSING
*/
virtual void setMinResponseThreshold(PxReal threshold) = 0;
/**
\brief Retrieve the constraint break force and torque thresholds
\return the minimum response threshold for a constraint row
*/
virtual PxReal getMinResponseThreshold() const = 0;
/**
\brief Fetch external owner of the constraint.
Provides a reference to the external owner of a constraint and a unique owner type ID.
\param[out] typeID Unique type identifier of the external object.
\return Reference to the external object which owns the constraint.
@see PxConstraintConnector.getExternalReference()
*/
virtual void* getExternalReference(PxU32& typeID) = 0;
/**
\brief Set the constraint functions for this constraint
\param[in] connector the constraint connector object by which the SDK communicates with the constraint.
\param[in] shaders the shader table for the constraint
@see PxConstraintConnector PxConstraintSolverPrep PxConstraintProject PxConstraintVisualize
*/
virtual void setConstraintFunctions(PxConstraintConnector& connector,
const PxConstraintShaderTable& shaders) = 0;
virtual const char* getConcreteTypeName() const { return "PxConstraint"; }
protected:
PX_INLINE PxConstraint(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags) {}
PX_INLINE PxConstraint(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
virtual ~PxConstraint() {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxConstraint", name) || PxBase::isKindOf(name); }
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,443 @@
//
// 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-2018 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_CONSTRAINTDESC
#define PX_PHYSICS_NX_CONSTRAINTDESC
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "foundation/PxFlags.h"
#include "foundation/PxVec3.h"
#include "common/PxBase.h"
#if !PX_DOXYGEN
namespace physx { namespace pvdsdk {
#endif
class PvdDataStream;
#if !PX_DOXYGEN
}}
#endif
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxConstraintConnector;
class PxRigidActor;
class PxScene;
class PxConstraintConnector;
class PxRenderBuffer;
class PxDeletionListener;
/**
\brief constraint row flags
These flags configure the post-processing of constraint rows and the behavior of the solver while solving constraints
*/
struct Px1DConstraintFlag
{
PX_CUDA_CALLABLE Px1DConstraintFlag(){}
enum Type
{
eSPRING = 1<<0, //!< whether the constraint is a spring. Mutually exclusive with eRESTITUTION. If set, eKEEPBIAS is ignored.
eACCELERATION_SPRING = 1<<1, //!< whether the constraint is a force or acceleration spring. Only valid if eSPRING is set.
eRESTITUTION = 1<<2, //!< whether the restitution model should be applied to generate the target velocity. Mutually exclusive with eSPRING. If restitution causes a bounces, eKEEPBIAS is ignored
eKEEPBIAS = 1<<3, //!< whether to keep the error term when solving for velocity. Ignored if restitution generates bounce, or eSPRING is set.
eOUTPUT_FORCE = 1<<4, //!< whether to accumulate the force value from this constraint in the force total that is reported for the constraint and tested for breakage
eHAS_DRIVE_LIMIT = 1<<5, //!< whether the constraint has a drive force limit (which will be scaled by dt unless PxConstraintFlag::eLIMITS_ARE_FORCES is set)
eANGULAR_CONSTRAINT = 1 << 6,//!< Whether this is an angular or linear constraint
eDRIVE_ROW = 1 << 7
};
};
typedef PxFlags<Px1DConstraintFlag::Type, PxU16> Px1DConstraintFlags;
PX_FLAGS_OPERATORS(Px1DConstraintFlag::Type, PxU16)
/**
\brief constraint type hints which the solver uses to optimize constraint handling
*/
struct PxConstraintSolveHint
{
enum Enum
{
eNONE = 0, //!< no special properties
eACCELERATION1 = 256, //!< a group of acceleration drive constraints with the same stiffness and drive parameters
eSLERP_SPRING = 258, //!< temporary special value to identify SLERP drive rows
eACCELERATION2 = 512, //!< a group of acceleration drive constraints with the same stiffness and drive parameters
eACCELERATION3 = 768, //!< a group of acceleration drive constraints with the same stiffness and drive parameters
eROTATIONAL_EQUALITY = 1024, //!< rotational equality constraints with no force limit and no velocity target
eROTATIONAL_INEQUALITY = 1025, //!< rotational inequality constraints with (0, PX_MAX_FLT) force limits
eEQUALITY = 2048, //!< equality constraints with no force limit and no velocity target
eINEQUALITY = 2049 //!< inequality constraints with (0, PX_MAX_FLT) force limits
};
};
/**
\brief A constraint
A constraint is expressed as a set of 1-dimensional constraint rows which define the required constraint
on the objects' velocities.
Each constraint is either a hard constraint or a spring. We define the velocity at the constraint to be
the quantity
v = body0vel.dot(lin0,ang0) - body1vel.dot(lin1, ang1)
For a hard constraint, the solver attempts to generate
1. a set of velocities for the objects which, when integrated, respect the constraint errors:
v + (geometricError / timestep) = velocityTarget
2. a set of velocities for the objects which respect the constraints:
v = velocityTarget
Hard constraints support restitution: if the impact velocity exceeds the bounce threshold, then the target velocity
of the constraint will be set to restitution * -v
Alternatively, the solver can attempt to resolve the velocity constraint as an implicit spring:
F = stiffness * -geometricError + damping * (velocityTarget - v)
where F is the constraint force or acceleration. Springs are fully implicit: that is, the force or acceleration
is a function of the position and velocity after the solve.
All constraints support limits on the minimum or maximum impulse applied.
*/
PX_ALIGN_PREFIX(16)
struct Px1DConstraint
{
PxVec3 linear0; //!< linear component of velocity jacobian in world space
PxReal geometricError; //!< geometric error of the constraint along this axis
PxVec3 angular0; //!< angular component of velocity jacobian in world space
PxReal velocityTarget; //!< velocity target for the constraint along this axis
PxVec3 linear1; //!< linear component of velocity jacobian in world space
PxReal minImpulse; //!< minimum impulse the solver may apply to enforce this constraint
PxVec3 angular1; //!< angular component of velocity jacobian in world space
PxReal maxImpulse; //!< maximum impulse the solver may apply to enforce this constraint
union
{
struct SpringModifiers
{
PxReal stiffness; //!< spring parameter, for spring constraints
PxReal damping; //!< damping parameter, for spring constraints
} spring;
struct RestitutionModifiers
{
PxReal restitution; //!< restitution parameter for determining additional "bounce"
PxReal velocityThreshold; //!< minimum impact velocity for bounce
} bounce;
} mods;
PxReal forInternalUse; //!< for internal use only
PxU16 flags; //!< a set of Px1DConstraintFlags
PxU16 solveHint; //!< constraint optimization hint, should be an element of PxConstraintSolveHint
}
PX_ALIGN_SUFFIX(16);
/**
\brief Flags for determining which components of the constraint should be visualized.
@see PxConstraintVisualize
*/
struct PxConstraintVisualizationFlag
{
enum Enum
{
eLOCAL_FRAMES = 1, //!< visualize constraint frames
eLIMITS = 2 //!< visualize constraint limits
};
};
PX_ALIGN_PREFIX(16)
struct PxConstraintInvMassScale
{
//= ATTENTION! =====================================================================================
// Changing the data layout of this class breaks the binary serialization format. See comments for
// PX_BINARY_SERIAL_VERSION. If a modification is required, please adjust the getBinaryMetaData
// function. If the modification is made on a custom branch, please change PX_BINARY_SERIAL_VERSION
// accordingly.
//==================================================================================================
PxReal linear0; //!< multiplier for inverse mass of body0
PxReal angular0; //!< multiplier for inverse MoI of body0
PxReal linear1; //!< multiplier for inverse mass of body1
PxReal angular1; //!< multiplier for inverse MoI of body1
PX_CUDA_CALLABLE PX_FORCE_INLINE PxConstraintInvMassScale(){}
PX_CUDA_CALLABLE PX_FORCE_INLINE PxConstraintInvMassScale(PxReal lin0, PxReal ang0, PxReal lin1, PxReal ang1) : linear0(lin0), angular0(ang0), linear1(lin1), angular1(ang1){}
}
PX_ALIGN_SUFFIX(16);
/** solver constraint generation shader
This function is called by the constraint solver framework. The function must be reentrant, since it may be called simultaneously
from multiple threads, and should access only the arguments passed into it.
Developers writing custom constraints are encouraged to read the documentation in the user guide and the implementation code in PhysXExtensions.
\param[out] constraints An array of solver constraint rows to be filled in
\param[out] bodyAWorldOffset The origin point (offset from the position vector of bodyA's center of mass) at which the constraint is resolved. This value does not affect how constraints are solved, only the constraint force reported.
\param[in] maxConstraints The size of the constraint buffer. At most this many constraints rows may be written
\param[out] invMassScale The inverse mass and inertia scales for the constraint
\param[in] constantBlock The constant data block
\param[in] bodyAToWorld The center of mass frame of the first constrained body (the identity transform if the first actor is static, or if a NULL actor pointer was provided for it)
\param[in] bodyBToWorld The center of mass frame of the second constrained body (the identity transform if the second actor is static, or if a NULL actor pointer was provided for it)
\param[in] useExtendedLimits Enables limit ranges outside of (-PI, PI)
\param[out] cAtW The world space location of body A's joint frame (position only)
\param[out] cBtW The world space location of body B's joint frame (position only)
\return the number of constraint rows written.
*/
typedef PxU32 (*PxConstraintSolverPrep)(Px1DConstraint* constraints,
PxVec3& bodyAWorldOffset,
PxU32 maxConstraints,
PxConstraintInvMassScale& invMassScale,
const void* constantBlock,
const PxTransform& bodyAToWorld,
const PxTransform& bodyBToWorld,
bool useExtendedLimits,
PxVec3& cAtW,
PxVec3& cBtW);
/** solver constraint projection shader
This function is called by the constraint post-solver framework. The function must be reentrant, since it may be called simultaneously
from multiple threads and should access only the arguments passed into it.
\param[in] constantBlock The constant data block
\param[out] bodyAToWorld The center of mass frame of the first constrained body (the identity if the actor is static or a NULL pointer was provided for it)
\param[out] bodyBToWorld The center of mass frame of the second constrained body (the identity if the actor is static or a NULL pointer was provided for it)
\param[in] projectToA True if the constraint should be projected by moving the second body towards the first, false if the converse
*/
typedef void (*PxConstraintProject)(const void* constantBlock,
PxTransform& bodyAToWorld,
PxTransform& bodyBToWorld,
bool projectToA);
/**
API used to visualize details about a constraint.
*/
class PxConstraintVisualizer
{
protected:
virtual ~PxConstraintVisualizer(){}
public:
/** Visualize joint frames
\param[in] parent Parent transformation
\param[in] child Child transformation
*/
virtual void visualizeJointFrames(const PxTransform& parent, const PxTransform& child) = 0;
/** Visualize joint linear limit
\param[in] t0 Base transformation
\param[in] t1 End transformation
\param[in] value Distance
\param[in] active State of the joint - active/inactive
*/
virtual void visualizeLinearLimit(const PxTransform& t0, const PxTransform& t1, PxReal value, bool active) = 0;
/** Visualize joint angular limit
\param[in] t0 Transformation for the visualization
\param[in] lower Lower limit angle
\param[in] upper Upper limit angle
\param[in] active State of the joint - active/inactive
*/
virtual void visualizeAngularLimit(const PxTransform& t0, PxReal lower, PxReal upper, bool active) = 0;
/** Visualize limit cone
\param[in] t Transformation for the visualization
\param[in] tanQSwingY Tangent of the quarter Y angle
\param[in] tanQSwingZ Tangent of the quarter Z angle
\param[in] active State of the joint - active/inactive
*/
virtual void visualizeLimitCone(const PxTransform& t, PxReal tanQSwingY, PxReal tanQSwingZ, bool active) = 0;
/** Visualize joint double cone
\param[in] t Transformation for the visualization
\param[in] angle Limit angle
\param[in] active State of the joint - active/inactive
*/
virtual void visualizeDoubleCone(const PxTransform& t, PxReal angle, bool active) = 0;
/** Visualize line
\param[in] p0 Start position
\param[in] p1 End postion
\param[in] color Color
*/
virtual void visualizeLine(const PxVec3& p0, const PxVec3& p1, PxU32 color) = 0;
};
/** solver constraint visualization function
This function is called by the constraint post-solver framework to visualize the constraint
\param[out] visualizer The render buffer to render to
\param[in] constantBlock The constant data block
\param[in] body0Transform The center of mass frame of the first constrained body (the identity if the actor is static, or a NULL pointer was provided for it)
\param[in] body1Transform The center of mass frame of the second constrained body (the identity if the actor is static, or a NULL pointer was provided for it)
\param[in] flags The visualization flags (PxConstraintVisualizationFlag)
@see PxRenderBuffer
*/
typedef void (*PxConstraintVisualize)(PxConstraintVisualizer& visualizer,
const void* constantBlock,
const PxTransform& body0Transform,
const PxTransform& body1Transform,
PxU32 flags);
struct PxPvdUpdateType
{
enum Enum
{
CREATE_INSTANCE,
RELEASE_INSTANCE,
UPDATE_ALL_PROPERTIES,
UPDATE_SIM_PROPERTIES
};
};
/**
\brief This class connects a custom constraint to the SDK
This class connects a custom constraint to the SDK, and functions are called by the SDK
to query the custom implementation for specific information to pass on to the application
or inform the constraint when the application makes calls into the SDK which will update
the custom constraint's internal implementation
*/
class PxConstraintConnector
{
public:
/**
when the constraint is marked dirty, this function is called at the start of the simulation
step for the SDK to copy the constraint data block.
*/
virtual void* prepareData() = 0;
/**
this function is called by the SDK to update PVD's view of it
*/
virtual bool updatePvdProperties(physx::pvdsdk::PvdDataStream& pvdConnection,
const PxConstraint* c,
PxPvdUpdateType::Enum updateType) const = 0;
/**
When the SDK deletes a PxConstraint object this function is called by the SDK. In general
custom constraints should not be deleted directly by applications: rather, the constraint
should respond to a release() request by calling PxConstraint::release(), then wait for
this call to release its own resources, so that even if the release() call occurs during
a simulation step, the deletion of the constraint is buffered until that step completes.
This function is also called when a PxConstraint object is deleted on cleanup due to
destruction of the PxPhysics object.
*/
virtual void onConstraintRelease() = 0;
/**
This function is called by the SDK when the CoM of one of the actors is moved. Since the
API specifies constraint positions relative to actors, and the constraint shader functions
are supplied with coordinates relative to bodies, some synchronization is usually required
when the application moves an object's center of mass.
*/
virtual void onComShift(PxU32 actor) = 0;
/**
This function is called by the SDK when the scene origin gets shifted and allows to adjust
custom data which contains world space transforms.
\note If the adjustments affect constraint shader data, it is necessary to call PxConstraint::markDirty()
to make sure that the data gets synced at the beginning of the next simulation step.
\param[in] shift Translation vector the origin is shifted by.
@see PxScene.shiftOrigin()
*/
virtual void onOriginShift(const PxVec3& shift) = 0;
/**
\brief Fetches external data for a constraint.
This function is used by the SDK to acquire a reference to the owner of a constraint and a unique
owner type ID. This information will be passed on when a breakable constraint breaks or when
#PxConstraint::getExternalReference() is called.
\param[out] typeID Unique type identifier of the external object. The value 0xffffffff is reserved and should not be used. Furthermore, if the PhysX extensions library is used, some other IDs are reserved already (see PxConstraintExtIDs)
\return Reference to the external object which owns the constraint.
@see PxConstraintInfo PxSimulationEventCallback.onConstraintBreak()
*/
virtual void* getExternalReference(PxU32& typeID) = 0;
/**
\brief Obtain a reference to a PxBase interface if the constraint has one.
If the constraint does not implement the PxBase interface, it should return NULL.
*/
virtual PxBase* getSerializable() = 0;
/**
\brief Obtain the shader function pointer used to prep rows for this constraint
*/
virtual PxConstraintSolverPrep getPrep() const = 0;
/**
\brief Obtain the pointer to the constraint's constant data
*/
virtual const void* getConstantBlock() const = 0;
/**
\brief virtual destructor
*/
virtual ~PxConstraintConnector() {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,583 @@
//
// 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-2018 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_CONTACT_H
#define PX_CONTACT_H
#include "foundation/PxVec3.h"
#include "foundation/PxAssert.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
#if PX_VC
#pragma warning(push)
#pragma warning(disable: 4324) // Padding was added at the end of a structure because of a __declspec(align) value.
#endif
#define PXC_CONTACT_NO_FACE_INDEX 0xffffffff
PX_ALIGN_PREFIX(16)
struct PxMassModificationProps
{
PxReal mInvMassScale0;
PxReal mInvInertiaScale0;
PxReal mInvMassScale1;
PxReal mInvInertiaScale1;
}
PX_ALIGN_SUFFIX(16);
/**
\brief Header for contact patch where all points share same material and normal
*/
PX_ALIGN_PREFIX(16)
struct PxContactPatch
{
enum PxContactPatchFlags
{
eHAS_FACE_INDICES = 1, //!< Indicates this contact stream has face indices.
eMODIFIABLE = 2, //!< Indicates this contact stream is modifiable.
eFORCE_NO_RESPONSE = 4, //!< Indicates this contact stream is notify-only (no contact response).
eHAS_MODIFIED_MASS_RATIOS = 8, //!< Indicates this contact stream has modified mass ratios
eHAS_TARGET_VELOCITY = 16, //!< Indicates this contact stream has target velocities set
eHAS_MAX_IMPULSE = 32, //!< Indicates this contact stream has max impulses set
eREGENERATE_PATCHES = 64, //!< Indicates this contact stream needs patches re-generated.
//!< This is required if the application modified either the contact normal or the material properties
eCOMPRESSED_MODIFIED_CONTACT = 128
};
PX_ALIGN(16, PxMassModificationProps mMassModification); //16
/**
\brief Contact normal
*/
PX_ALIGN(16, PxVec3 normal); //28
/**
\brief Restitution coefficient
*/
PxReal restitution; //32
PxReal dynamicFriction; //36
PxReal staticFriction; //40
PxU8 startContactIndex; //41
PxU8 nbContacts; //42 //Can be a U8
PxU8 materialFlags; //43 //Can be a U16
PxU8 internalFlags; //44 //Can be a U16
PxU16 materialIndex0; //46 //Can be a U16
PxU16 materialIndex1; //48 //Can be a U16
}
PX_ALIGN_SUFFIX(16);
/**
\brief Contact point data including face (feature) indices
*/
PX_ALIGN_PREFIX(16)
struct PxContact
{
/**
\brief Contact point in world space
*/
PxVec3 contact; //12
/**
\brief Separation value (negative implies penetration).
*/
PxReal separation; //16
}
PX_ALIGN_SUFFIX(16);
PX_ALIGN_PREFIX(16)
struct PxExtendedContact : public PxContact
{
/**
\brief Target velocity
*/
PX_ALIGN(16, PxVec3 targetVelocity); //28
/**
\brief Maximum impulse
*/
PxReal maxImpulse; //32
}
PX_ALIGN_SUFFIX(16);
/**
\brief A modifiable contact point. This has additional fields per-contact to permit modification by user.
\note Not all fields are currently exposed to the user.
*/
PX_ALIGN_PREFIX(16)
struct PxModifiableContact : public PxExtendedContact
{
/**
\brief Contact normal
*/
PX_ALIGN(16, PxVec3 normal); //44
/**
\brief Restitution coefficient
*/
PxReal restitution; //48
/**
\brief Material Flags
*/
PxU32 materialFlags; //52
/**
\brief Shape A's material index
*/
PxU16 materialIndex0; //54
/**
\brief Shape B's material index
*/
PxU16 materialIndex1; //56
/**
\brief static friction coefficient
*/
PxReal staticFriction; //60
/**
\brief dynamic friction coefficient
*/
PxReal dynamicFriction; //64
}
PX_ALIGN_SUFFIX(16);
/**
\brief A class to iterate over a compressed contact stream. This supports read-only access to the various contact formats.
*/
struct PxContactStreamIterator
{
enum StreamFormat
{
eSIMPLE_STREAM,
eMODIFIABLE_STREAM,
eCOMPRESSED_MODIFIABLE_STREAM
};
/**
\brief Utility zero vector to optimize functions returning zero vectors when a certain flag isn't set.
\note This allows us to return by reference instead of having to return by value. Returning by value will go via memory (registers -> stack -> registers), which can
cause performance issues on certain platforms.
*/
PxVec3 zero;
/**
\brief The patch headers.
*/
const PxContactPatch* patch;
/**
\brief The contacts
*/
const PxContact* contact;
/**
\brief The contact triangle face index
*/
const PxU32* faceIndice;
/**
\brief The total number of patches in this contact stream
*/
PxU32 totalPatches;
/**
\brief The total number of contact points in this stream
*/
PxU32 totalContacts;
/**
\brief The current contact index
*/
PxU32 nextContactIndex;
/**
\brief The current patch Index
*/
PxU32 nextPatchIndex;
/*
\brief Size of contact patch header
\note This varies whether the patch is modifiable or not.
*/
PxU32 contactPatchHeaderSize;
/**
\brief Contact point size
\note This varies whether the patch has feature indices or is modifiable.
*/
PxU32 contactPointSize;
/**
\brief The stream format
*/
StreamFormat mStreamFormat;
/**
\brief Indicates whether this stream is notify-only or not.
*/
PxU32 forceNoResponse;
bool pointStepped;
PxU32 hasFaceIndices;
/**
\brief Constructor
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxContactStreamIterator(const PxU8* contactPatches, const PxU8* contactPoints, const PxU32* contactFaceIndices, PxU32 nbPatches, PxU32 nbContacts)
: zero(0.f)
{
bool modify = false;
bool compressedModify = false;
bool response = false;
bool indices = false;
PxU32 pointSize = 0;
PxU32 patchHeaderSize = sizeof(PxContactPatch);
const PxContactPatch* patches = reinterpret_cast<const PxContactPatch*>(contactPatches);
if(patches)
{
modify = (patches->internalFlags & PxContactPatch::eMODIFIABLE) != 0;
compressedModify = (patches->internalFlags & PxContactPatch::eCOMPRESSED_MODIFIED_CONTACT) != 0;
indices = (patches->internalFlags & PxContactPatch::eHAS_FACE_INDICES) != 0;
patch = patches;
contact = reinterpret_cast<const PxContact*>(contactPoints);
faceIndice = contactFaceIndices;
pointSize = compressedModify ? sizeof(PxExtendedContact) : modify ? sizeof(PxModifiableContact) : sizeof(PxContact);
response = (patch->internalFlags & PxContactPatch::eFORCE_NO_RESPONSE) == 0;
}
mStreamFormat = compressedModify ? eCOMPRESSED_MODIFIABLE_STREAM : modify ? eMODIFIABLE_STREAM : eSIMPLE_STREAM;
hasFaceIndices = PxU32(indices);
forceNoResponse = PxU32(!response);
contactPatchHeaderSize = patchHeaderSize;
contactPointSize = pointSize;
nextPatchIndex = 0;
nextContactIndex = 0;
totalContacts = nbContacts;
totalPatches = nbPatches;
pointStepped = false;
}
/**
\brief Returns whether there are more patches in this stream.
\return Whether there are more patches in this stream.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE bool hasNextPatch() const
{
return nextPatchIndex < totalPatches;
}
/**
\brief Returns the total contact count.
\return Total contact count.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxU32 getTotalContactCount() const
{
return totalContacts;
}
PX_CUDA_CALLABLE PX_FORCE_INLINE PxU32 getTotalPatchCount() const
{
return totalPatches;
}
/**
\brief Advances iterator to next contact patch.
*/
PX_CUDA_CALLABLE PX_INLINE void nextPatch()
{
PX_ASSERT(nextPatchIndex < totalPatches);
if(nextPatchIndex)
{
if(nextContactIndex < patch->nbContacts)
{
PxU32 nbToStep = patch->nbContacts - this->nextContactIndex;
contact = reinterpret_cast<const PxContact*>(reinterpret_cast<const PxU8*>(contact) + contactPointSize * nbToStep);
}
patch = reinterpret_cast<const PxContactPatch*>(reinterpret_cast<const PxU8*>(patch) + contactPatchHeaderSize);
}
nextPatchIndex++;
nextContactIndex = 0;
}
/**
\brief Returns if the current patch has more contacts.
\return If there are more contacts in the current patch.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE bool hasNextContact() const
{
return nextContactIndex < (patch->nbContacts);
}
/**
\brief Advances to the next contact in the patch.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE void nextContact()
{
PX_ASSERT(nextContactIndex < patch->nbContacts);
if(pointStepped)
{
contact = reinterpret_cast<const PxContact*>(reinterpret_cast<const PxU8*>(contact) + contactPointSize);
faceIndice++;
}
nextContactIndex++;
pointStepped = true;
}
/**
\brief Gets the current contact's normal
\return The current contact's normal.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE const PxVec3& getContactNormal() const
{
return getContactPatch().normal;
}
/**
\brief Gets the inverse mass scale for body 0.
\return The inverse mass scale for body 0.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxReal getInvMassScale0() const
{
return patch->mMassModification.mInvMassScale0;
}
/**
\brief Gets the inverse mass scale for body 1.
\return The inverse mass scale for body 1.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxReal getInvMassScale1() const
{
return patch->mMassModification.mInvMassScale1;
}
/**
\brief Gets the inverse inertia scale for body 0.
\return The inverse inertia scale for body 0.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxReal getInvInertiaScale0() const
{
return patch->mMassModification.mInvInertiaScale0;
}
/**
\brief Gets the inverse inertia scale for body 1.
\return The inverse inertia scale for body 1.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxReal getInvInertiaScale1() const
{
return patch->mMassModification.mInvInertiaScale1;
}
/**
\brief Gets the contact's max impulse.
\return The contact's max impulse.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxReal getMaxImpulse() const
{
return mStreamFormat != eSIMPLE_STREAM ? getExtendedContact().maxImpulse : PX_MAX_REAL;
}
/**
\brief Gets the contact's target velocity.
\return The contact's target velocity.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE const PxVec3& getTargetVel() const
{
return mStreamFormat != eSIMPLE_STREAM ? getExtendedContact().targetVelocity : zero;
}
/**
\brief Gets the contact's contact point.
\return The contact's contact point.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE const PxVec3& getContactPoint() const
{
return contact->contact;
}
/**
\brief Gets the contact's separation.
\return The contact's separation.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxReal getSeparation() const
{
return contact->separation;
}
/**
\brief Gets the contact's face index for shape 0.
\return The contact's face index for shape 0.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxU32 getFaceIndex0() const
{
return PXC_CONTACT_NO_FACE_INDEX;
}
/**
\brief Gets the contact's face index for shape 1.
\return The contact's face index for shape 1.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxU32 getFaceIndex1() const
{
return hasFaceIndices ? *faceIndice : PXC_CONTACT_NO_FACE_INDEX;
}
/**
\brief Gets the contact's static friction coefficient.
\return The contact's static friction coefficient.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxReal getStaticFriction() const
{
return getContactPatch().staticFriction;
}
/**
\brief Gets the contact's static dynamic coefficient.
\return The contact's static dynamic coefficient.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxReal getDynamicFriction() const
{
return getContactPatch().dynamicFriction;
}
/**
\brief Gets the contact's restitution coefficient.
\return The contact's restitution coefficient.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxReal getRestitution() const
{
return getContactPatch().restitution;
}
/**
\brief Gets the contact's material flags.
\return The contact's material flags.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxU32 getMaterialFlags() const
{
return getContactPatch().materialFlags;
}
/**
\brief Gets the contact's material index for shape 0.
\return The contact's material index for shape 0.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxU16 getMaterialIndex0() const
{
return PxU16(getContactPatch().materialIndex0);
}
/**
\brief Gets the contact's material index for shape 1.
\return The contact's material index for shape 1.
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE PxU16 getMaterialIndex1() const
{
return PxU16(getContactPatch().materialIndex1);
}
/**
\brief Advances the contact stream iterator to a specific contact index.
*/
bool advanceToIndex(const PxU32 initialIndex)
{
PX_ASSERT(this->nextPatchIndex == 0 && this->nextContactIndex == 0);
PxU32 numToAdvance = initialIndex;
if(numToAdvance == 0)
{
PX_ASSERT(hasNextPatch());
nextPatch();
return true;
}
while(numToAdvance)
{
while(hasNextPatch())
{
nextPatch();
PxU32 patchSize = patch->nbContacts;
if(numToAdvance <= patchSize)
{
contact = reinterpret_cast<const PxContact*>(reinterpret_cast<const PxU8*>(contact) + contactPointSize * numToAdvance);
nextContactIndex += numToAdvance;
return true;
}
else
{
numToAdvance -= patchSize;
}
}
}
return false;
}
private:
/**
\brief Internal helper
*/
PX_CUDA_CALLABLE PX_FORCE_INLINE const PxContactPatch& getContactPatch() const
{
return *static_cast<const PxContactPatch*>(patch);
}
PX_CUDA_CALLABLE PX_FORCE_INLINE const PxExtendedContact& getExtendedContact() const
{
PX_ASSERT(mStreamFormat == eMODIFIABLE_STREAM || mStreamFormat == eCOMPRESSED_MODIFIABLE_STREAM);
return *static_cast<const PxExtendedContact*>(contact);
}
};
#if PX_VC
#pragma warning(pop)
#endif
#if !PX_DOXYGEN
} // namespace physx
#endif
#endif

View File

@ -0,0 +1,486 @@
//
// 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-2018 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_CONTACT_MODIFY_CALLBACK
#define PX_CONTACT_MODIFY_CALLBACK
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "PxShape.h"
#include "PxContact.h"
#include "foundation/PxTransform.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxShape;
/**
\brief An array of contact points, as passed to contact modification.
The word 'set' in the name does not imply that duplicates are filtered in any
way. This initial set of contacts does potentially get reduced to a smaller
set before being passed to the solver.
You can use the accessors to read and write contact properties. The number of
contacts is immutable, other than being able to disable contacts using ignore().
@see PxContactModifyCallback, PxModifiableContact
*/
class PxContactSet
{
public:
/**
\brief Get the position of a specific contact point in the set.
@see PxModifiableContact.point
*/
PX_FORCE_INLINE const PxVec3& getPoint(PxU32 i) const { return mContacts[i].contact; }
/**
\brief Alter the position of a specific contact point in the set.
@see PxModifiableContact.point
*/
PX_FORCE_INLINE void setPoint(PxU32 i, const PxVec3& p) { mContacts[i].contact = p; }
/**
\brief Get the contact normal of a specific contact point in the set.
@see PxModifiableContact.normal
*/
PX_FORCE_INLINE const PxVec3& getNormal(PxU32 i) const { return mContacts[i].normal; }
/**
\brief Alter the contact normal of a specific contact point in the set.
\note Changing the normal can cause contact points to be ignored.
@see PxModifiableContact.normal
*/
PX_FORCE_INLINE void setNormal(PxU32 i, const PxVec3& n)
{
PxContactPatch* patch = getPatch();
patch->internalFlags |= PxContactPatch::eREGENERATE_PATCHES;
mContacts[i].normal = n;
}
/**
\brief Get the separation of a specific contact point in the set.
@see PxModifiableContact.separation
*/
PX_FORCE_INLINE PxReal getSeparation(PxU32 i) const { return mContacts[i].separation; }
/**
\brief Alter the separation of a specific contact point in the set.
@see PxModifiableContact.separation
*/
PX_FORCE_INLINE void setSeparation(PxU32 i, PxReal s) { mContacts[i].separation = s; }
/**
\brief Get the target velocity of a specific contact point in the set.
@see PxModifiableContact.targetVelocity
*/
PX_FORCE_INLINE const PxVec3& getTargetVelocity(PxU32 i) const { return mContacts[i].targetVelocity; }
/**
\brief Alter the target velocity of a specific contact point in the set.
@see PxModifiableContact.targetVelocity
*/
PX_FORCE_INLINE void setTargetVelocity(PxU32 i, const PxVec3& v)
{
PxContactPatch* patch = getPatch();
patch->internalFlags |= PxContactPatch::eHAS_TARGET_VELOCITY;
mContacts[i].targetVelocity = v;
}
/**
\brief Get the face index with respect to the first shape of the pair for a specific contact point in the set.
@see PxModifiableContact.internalFaceIndex0
*/
PX_FORCE_INLINE PxU32 getInternalFaceIndex0(PxU32 i) { PX_UNUSED(i); return PXC_CONTACT_NO_FACE_INDEX; }
/**
\brief Get the face index with respect to the second shape of the pair for a specific contact point in the set.
@see PxModifiableContact.internalFaceIndex1
*/
PX_FORCE_INLINE PxU32 getInternalFaceIndex1(PxU32 i)
{
PxContactPatch* patch = getPatch();
if (patch->internalFlags & PxContactPatch::eHAS_FACE_INDICES)
{
return reinterpret_cast<PxU32*>(mContacts + mCount)[mCount + i];
}
return PXC_CONTACT_NO_FACE_INDEX;
}
/**
\brief Get the maximum impulse for a specific contact point in the set.
@see PxModifiableContact.maxImpulse
*/
PX_FORCE_INLINE PxReal getMaxImpulse(PxU32 i) const { return mContacts[i].maxImpulse; }
/**
\brief Alter the maximum impulse for a specific contact point in the set.
\note Must be nonnegative. If set to zero, the contact point will be ignored
@see PxModifiableContact.maxImpulse
*/
PX_FORCE_INLINE void setMaxImpulse(PxU32 i, PxReal s)
{
PxContactPatch* patch = getPatch();
patch->internalFlags |= PxContactPatch::eHAS_MAX_IMPULSE;
mContacts[i].maxImpulse = s;
}
/**
\brief Get the restitution coefficient for a specific contact point in the set.
@see PxModifiableContact.restitution
*/
PX_FORCE_INLINE PxReal getRestitution(PxU32 i) const { return mContacts[i].restitution; }
/**
\brief Alter the restitution coefficient for a specific contact point in the set.
\note Valid ranges [0,1]
@see PxModifiableContact.restitution
*/
PX_FORCE_INLINE void setRestitution(PxU32 i, PxReal r)
{
PxContactPatch* patch = getPatch();
patch->internalFlags |= PxContactPatch::eREGENERATE_PATCHES;
mContacts[i].restitution = r;
}
/**
\brief Get the static friction coefficient for a specific contact point in the set.
@see PxModifiableContact.staticFriction
*/
PX_FORCE_INLINE PxReal getStaticFriction(PxU32 i) const { return mContacts[i].staticFriction; }
/**
\brief Alter the static friction coefficient for a specific contact point in the set.
@see PxModifiableContact.staticFriction
*/
PX_FORCE_INLINE void setStaticFriction(PxU32 i, PxReal f)
{
PxContactPatch* patch = getPatch();
patch->internalFlags |= PxContactPatch::eREGENERATE_PATCHES;
mContacts[i].staticFriction = f;
}
/**
\brief Get the static friction coefficient for a specific contact point in the set.
@see PxModifiableContact.dynamicFriction
*/
PX_FORCE_INLINE PxReal getDynamicFriction(PxU32 i) const { return mContacts[i].dynamicFriction; }
/**
\brief Alter the static dynamic coefficient for a specific contact point in the set.
@see PxModifiableContact.dynamic
*/
PX_FORCE_INLINE void setDynamicFriction(PxU32 i, PxReal f)
{
PxContactPatch* patch = getPatch();
patch->internalFlags |= PxContactPatch::eREGENERATE_PATCHES;
mContacts[i].dynamicFriction = f;
}
/**
\brief Ignore the contact point.
If a contact point is ignored then no force will get applied at this point. This can be used to disable collision in certain areas of a shape, for example.
*/
PX_FORCE_INLINE void ignore(PxU32 i) { mContacts[i].maxImpulse = 0.f; }
/**
\brief The number of contact points in the set.
*/
PX_FORCE_INLINE PxU32 size() const { return mCount; }
/**
\brief Returns the invMassScale of body 0
A value < 1.0 makes this contact treat the body as if it had larger mass. A value of 0.f makes this contact
treat the body as if it had infinite mass. Any value > 1.f makes this contact treat the body as if it had smaller mass.
*/
PX_FORCE_INLINE PxReal getInvMassScale0() const
{
PxContactPatch* patch = getPatch();
return patch->mMassModification.mInvMassScale0;
}
/**
\brief Returns the invMassScale of body 1
A value < 1.0 makes this contact treat the body as if it had larger mass. A value of 0.f makes this contact
treat the body as if it had infinite mass. Any value > 1.f makes this contact treat the body as if it had smaller mass.
*/
PX_FORCE_INLINE PxReal getInvMassScale1() const
{
PxContactPatch* patch = getPatch();
return patch->mMassModification.mInvMassScale1;
}
/**
\brief Returns the invInertiaScale of body 0
A value < 1.0 makes this contact treat the body as if it had larger inertia. A value of 0.f makes this contact
treat the body as if it had infinite inertia. Any value > 1.f makes this contact treat the body as if it had smaller inertia.
*/
PX_FORCE_INLINE PxReal getInvInertiaScale0() const
{
PxContactPatch* patch = getPatch();
return patch->mMassModification.mInvInertiaScale0;
}
/**
\brief Returns the invInertiaScale of body 1
A value < 1.0 makes this contact treat the body as if it had larger inertia. A value of 0.f makes this contact
treat the body as if it had infinite inertia. Any value > 1.f makes this contact treat the body as if it had smaller inertia.
*/
PX_FORCE_INLINE PxReal getInvInertiaScale1() const
{
PxContactPatch* patch = getPatch();
return patch->mMassModification.mInvInertiaScale1;
}
/**
\brief Sets the invMassScale of body 0
This can be set to any value in the range [0, PX_MAX_F32). A value < 1.0 makes this contact treat the body as if it had larger mass. A value of 0.f makes this contact
treat the body as if it had infinite mass. Any value > 1.f makes this contact treat the body as if it had smaller mass.
*/
PX_FORCE_INLINE void setInvMassScale0(const PxReal scale)
{
PxContactPatch* patch = getPatch();
patch->mMassModification.mInvMassScale0 = scale;
patch->internalFlags |= PxContactPatch::eHAS_MODIFIED_MASS_RATIOS;
}
/**
\brief Sets the invMassScale of body 1
This can be set to any value in the range [0, PX_MAX_F32). A value < 1.0 makes this contact treat the body as if it had larger mass. A value of 0.f makes this contact
treat the body as if it had infinite mass. Any value > 1.f makes this contact treat the body as if it had smaller mass.
*/
PX_FORCE_INLINE void setInvMassScale1(const PxReal scale)
{
PxContactPatch* patch = getPatch();
patch->mMassModification.mInvMassScale1 = scale;
patch->internalFlags |= PxContactPatch::eHAS_MODIFIED_MASS_RATIOS;
}
/**
\brief Sets the invInertiaScale of body 0
This can be set to any value in the range [0, PX_MAX_F32). A value < 1.0 makes this contact treat the body as if it had larger inertia. A value of 0.f makes this contact
treat the body as if it had infinite inertia. Any value > 1.f makes this contact treat the body as if it had smaller inertia.
*/
PX_FORCE_INLINE void setInvInertiaScale0(const PxReal scale)
{
PxContactPatch* patch = getPatch();
patch->mMassModification.mInvInertiaScale0 = scale;
patch->internalFlags |= PxContactPatch::eHAS_MODIFIED_MASS_RATIOS;
}
/**
\brief Sets the invInertiaScale of body 1
This can be set to any value in the range [0, PX_MAX_F32). A value < 1.0 makes this contact treat the body as if it had larger inertia. A value of 0.f makes this contact
treat the body as if it had infinite inertia. Any value > 1.f makes this contact treat the body as if it had smaller inertia.
*/
PX_FORCE_INLINE void setInvInertiaScale1(const PxReal scale)
{
PxContactPatch* patch = getPatch();
patch->mMassModification.mInvInertiaScale1 = scale;
patch->internalFlags |= PxContactPatch::eHAS_MODIFIED_MASS_RATIOS;
}
protected:
PX_FORCE_INLINE PxContactPatch* getPatch() const
{
const size_t headerOffset = sizeof(PxContactPatch)*mCount;
return reinterpret_cast<PxContactPatch*>(reinterpret_cast<PxU8*>(mContacts) - headerOffset);
}
PxU32 mCount; //!< Number of contact points in the set
PxModifiableContact* mContacts; //!< The contact points of the set
};
/**
\brief An array of instances of this class is passed to PxContactModifyCallback::onContactModify().
@see PxContactModifyCallback
*/
class PxContactModifyPair
{
public:
/**
\brief The actors which make up the pair in contact.
Note that these are the actors as seen by the simulation, and may have been deleted since the simulation step started.
*/
const PxRigidActor* actor[2];
/**
\brief The shapes which make up the pair in contact.
Note that these are the shapes as seen by the simulation, and may have been deleted since the simulation step started.
*/
const PxShape* shape[2];
/**
\brief The shape to world transforms of the two shapes.
These are the transforms as the simulation engine sees them, and may have been modified by the application
since the simulation step started.
*/
PxTransform transform[2];
/**
\brief An array of contact points between these two shapes.
*/
PxContactSet contacts;
};
/**
\brief An interface class that the user can implement in order to modify contact constraints.
<b>Threading:</b> It is <b>necessary</b> to make this class thread safe as it will be called in the context of the
simulation thread. It might also be necessary to make it reentrant, since some calls can be made by multi-threaded
parts of the physics engine.
You can enable the use of this contact modification callback by raising the flag PxPairFlag::eMODIFY_CONTACTS in
the filter shader/callback (see #PxSimulationFilterShader) for a pair of rigid body objects.
Please note:
+ Raising the contact modification flag will not wake the actors up automatically.
+ It is not possible to turn off the performance degradation by simply removing the callback from the scene, the
filter shader/callback has to be used to clear the contact modification flag.
+ The contacts will only be reported as long as the actors are awake. There will be no callbacks while the actors are sleeping.
@see PxScene.setContactModifyCallback() PxScene.getContactModifyCallback()
*/
class PxContactModifyCallback
{
public:
/**
\brief Passes modifiable arrays of contacts to the application.
The initial contacts are as determined fresh each frame by collision detection.
The number of contacts can not be changed, so you cannot add your own contacts. You may however
disable contacts using PxContactSet::ignore().
@see PxContactModifyPair
*/
virtual void onContactModify(PxContactModifyPair* const pairs, PxU32 count) = 0;
protected:
virtual ~PxContactModifyCallback(){}
};
/**
\brief An interface class that the user can implement in order to modify CCD contact constraints.
<b>Threading:</b> It is <b>necessary</b> to make this class thread safe as it will be called in the context of the
simulation thread. It might also be necessary to make it reentrant, since some calls can be made by multi-threaded
parts of the physics engine.
You can enable the use of this contact modification callback by raising the flag PxPairFlag::eMODIFY_CONTACTS in
the filter shader/callback (see #PxSimulationFilterShader) for a pair of rigid body objects.
Please note:
+ Raising the contact modification flag will not wake the actors up automatically.
+ It is not possible to turn off the performance degradation by simply removing the callback from the scene, the
filter shader/callback has to be used to clear the contact modification flag.
+ The contacts will only be reported as long as the actors are awake. There will be no callbacks while the actors are sleeping.
@see PxScene.setContactModifyCallback() PxScene.getContactModifyCallback()
*/
class PxCCDContactModifyCallback
{
public:
/**
\brief Passes modifiable arrays of contacts to the application.
The initial contacts are as determined fresh each frame by collision detection.
The number of contacts can not be changed, so you cannot add your own contacts. You may however
disable contacts using PxContactSet::ignore().
@see PxContactModifyPair
*/
virtual void onCCDContactModify(PxContactModifyPair* const pairs, PxU32 count) = 0;
protected:
virtual ~PxCCDContactModifyCallback(){}
};
#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-2018 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_DELETIONLISTENER
#define PX_PHYSICS_NX_DELETIONLISTENER
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "common/PxBase.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Flags specifying deletion event types.
@see PxDeletionListener::onRelease PxPhysics.registerDeletionListener()
*/
struct PxDeletionEventFlag
{
enum Enum
{
eUSER_RELEASE = (1<<0), //!< The user has called release on an object.
eMEMORY_RELEASE = (1<<1) //!< The destructor of an object has been called and the memory has been released.
};
};
/**
\brief Collection of set bits defined in PxDeletionEventFlag.
@see PxDeletionEventFlag
*/
typedef PxFlags<PxDeletionEventFlag::Enum,PxU8> PxDeletionEventFlags;
PX_FLAGS_OPERATORS(PxDeletionEventFlag::Enum,PxU8)
/**
\brief interface to get notification on object deletion
*/
class PxDeletionListener
{
public:
/**
\brief Notification if an object or its memory gets released
If release() gets called on a PxBase object, an eUSER_RELEASE event will get fired immediately. The object state can be queried in the callback but
it is not allowed to change the state. Furthermore, when reading from the object it is the user's responsibility to make sure that no other thread
is writing at the same time to the object (this includes the simulation itself, i.e., #PxScene::fetchResults() must not get called at the same time).
Calling release() on a PxBase object does not necessarily trigger its destructor immediately. For example, the object can be shared and might still
be referenced by other objects or the simulation might still be running and accessing the object state. In such cases the destructor will be called
as soon as it is safe to do so. After the destruction of the object and its memory, an eMEMORY_RELEASE event will get fired. In this case it is not
allowed to dereference the object pointer in the callback.
\param[in] observed The object for which the deletion event gets fired.
\param[in] userData The user data pointer of the object for which the deletion event gets fired. Not available for all object types in which case it will be set to 0.
\param[in] deletionEvent The type of deletion event. Do not dereference the object pointer argument if the event is eMEMORY_RELEASE.
*/
virtual void onRelease(const PxBase* observed, void* userData, PxDeletionEventFlag::Enum deletionEvent) = 0;
protected:
PxDeletionListener() {}
virtual ~PxDeletionListener() {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,733 @@
//
// 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-2018 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_FILTERING
#define PX_PHYSICS_NX_FILTERING
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "foundation/PxFlags.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxActor;
class PxShape;
static const PxU32 INVALID_FILTER_PAIR_INDEX = 0xffffffff;
/**
\brief Collection of flags describing the actions to take for a collision pair.
@see PxPairFlags PxSimulationFilterShader.filter() PxSimulationFilterCallback
*/
struct PxPairFlag
{
enum Enum
{
/**
\brief Process the contacts of this collision pair in the dynamics solver.
\note Only takes effect if the colliding actors are rigid bodies.
*/
eSOLVE_CONTACT = (1<<0),
/**
\brief Call contact modification callback for this collision pair
\note Only takes effect if the colliding actors are rigid bodies.
@see PxContactModifyCallback
*/
eMODIFY_CONTACTS = (1<<1),
/**
\brief Call contact report callback or trigger callback when this collision pair starts to be in contact.
If one of the two collision objects is a trigger shape (see #PxShapeFlag::eTRIGGER_SHAPE)
then the trigger callback will get called as soon as the other object enters the trigger volume.
If none of the two collision objects is a trigger shape then the contact report callback will get
called when the actors of this collision pair start to be in contact.
\note Only takes effect if the colliding actors are rigid bodies.
\note Only takes effect if eDETECT_DISCRETE_CONTACT or eDETECT_CCD_CONTACT is raised
@see PxSimulationEventCallback.onContact() PxSimulationEventCallback.onTrigger()
*/
eNOTIFY_TOUCH_FOUND = (1<<2),
/**
\brief Call contact report callback while this collision pair is in contact
If none of the two collision objects is a trigger shape then the contact report callback will get
called while the actors of this collision pair are in contact.
\note Triggers do not support this event. Persistent trigger contacts need to be tracked separately by observing eNOTIFY_TOUCH_FOUND/eNOTIFY_TOUCH_LOST events.
\note Only takes effect if the colliding actors are rigid bodies.
\note No report will get sent if the objects in contact are sleeping.
\note Only takes effect if eDETECT_DISCRETE_CONTACT or eDETECT_CCD_CONTACT is raised
\note If this flag gets enabled while a pair is in touch already, there will be no eNOTIFY_TOUCH_PERSISTS events until the pair loses and regains touch.
@see PxSimulationEventCallback.onContact() PxSimulationEventCallback.onTrigger()
*/
eNOTIFY_TOUCH_PERSISTS = (1<<3),
/**
\brief Call contact report callback or trigger callback when this collision pair stops to be in contact
If one of the two collision objects is a trigger shape (see #PxShapeFlag::eTRIGGER_SHAPE)
then the trigger callback will get called as soon as the other object leaves the trigger volume.
If none of the two collision objects is a trigger shape then the contact report callback will get
called when the actors of this collision pair stop to be in contact.
\note Only takes effect if the colliding actors are rigid bodies.
\note This event will also get triggered if one of the colliding objects gets deleted.
\note Only takes effect if eDETECT_DISCRETE_CONTACT or eDETECT_CCD_CONTACT is raised
@see PxSimulationEventCallback.onContact() PxSimulationEventCallback.onTrigger()
*/
eNOTIFY_TOUCH_LOST = (1<<4),
/**
\brief Call contact report callback when this collision pair is in contact during CCD passes.
If CCD with multiple passes is enabled, then a fast moving object might bounce on and off the same
object multiple times. Hence, the same pair might be in contact multiple times during a simulation step.
This flag will make sure that all the detected collision during CCD will get reported. For performance
reasons, the system can not always tell whether the contact pair lost touch in one of the previous CCD
passes and thus can also not always tell whether the contact is new or has persisted. eNOTIFY_TOUCH_CCD
just reports when the two collision objects were detected as being in contact during a CCD pass.
\note Only takes effect if the colliding actors are rigid bodies.
\note Trigger shapes are not supported.
\note Only takes effect if eDETECT_CCD_CONTACT is raised
@see PxSimulationEventCallback.onContact() PxSimulationEventCallback.onTrigger()
*/
eNOTIFY_TOUCH_CCD = (1<<5),
/**
\brief Call contact report callback when the contact force between the actors of this collision pair exceeds one of the actor-defined force thresholds.
\note Only takes effect if the colliding actors are rigid bodies.
\note Only takes effect if eDETECT_DISCRETE_CONTACT or eDETECT_CCD_CONTACT is raised
@see PxSimulationEventCallback.onContact()
*/
eNOTIFY_THRESHOLD_FORCE_FOUND = (1<<6),
/**
\brief Call contact report callback when the contact force between the actors of this collision pair continues to exceed one of the actor-defined force thresholds.
\note Only takes effect if the colliding actors are rigid bodies.
\note If a pair gets re-filtered and this flag has previously been disabled, then the report will not get fired in the same frame even if the force threshold has been reached in the
previous one (unless #eNOTIFY_THRESHOLD_FORCE_FOUND has been set in the previous frame).
\note Only takes effect if eDETECT_DISCRETE_CONTACT or eDETECT_CCD_CONTACT is raised
@see PxSimulationEventCallback.onContact()
*/
eNOTIFY_THRESHOLD_FORCE_PERSISTS = (1<<7),
/**
\brief Call contact report callback when the contact force between the actors of this collision pair falls below one of the actor-defined force thresholds (includes the case where this collision pair stops being in contact).
\note Only takes effect if the colliding actors are rigid bodies.
\note If a pair gets re-filtered and this flag has previously been disabled, then the report will not get fired in the same frame even if the force threshold has been reached in the
previous one (unless #eNOTIFY_THRESHOLD_FORCE_FOUND or #eNOTIFY_THRESHOLD_FORCE_PERSISTS has been set in the previous frame).
\note Only takes effect if eDETECT_DISCRETE_CONTACT or eDETECT_CCD_CONTACT is raised
@see PxSimulationEventCallback.onContact()
*/
eNOTIFY_THRESHOLD_FORCE_LOST = (1<<8),
/**
\brief Provide contact points in contact reports for this collision pair.
\note Only takes effect if the colliding actors are rigid bodies and if used in combination with the flags eNOTIFY_TOUCH_... or eNOTIFY_THRESHOLD_FORCE_...
\note Only takes effect if eDETECT_DISCRETE_CONTACT or eDETECT_CCD_CONTACT is raised
@see PxSimulationEventCallback.onContact() PxContactPair PxContactPair.extractContacts()
*/
eNOTIFY_CONTACT_POINTS = (1<<9),
/**
\brief This flag is used to indicate whether this pair generates discrete collision detection contacts.
\note Contacts are only responded to if eSOLVE_CONTACT is enabled.
*/
eDETECT_DISCRETE_CONTACT = (1<<10),
/**
\brief This flag is used to indicate whether this pair generates CCD contacts.
\note The contacts will only be responded to if eSOLVE_CONTACT is enabled on this pair.
\note The scene must have PxSceneFlag::eENABLE_CCD enabled to use this feature.
\note Non-static bodies of the pair should have PxRigidBodyFlag::eENABLE_CCD specified for this feature to work correctly.
\note This flag is not supported with trigger shapes. However, CCD trigger events can be emulated using non-trigger shapes
and requesting eNOTIFY_TOUCH_FOUND and eNOTIFY_TOUCH_LOST and not raising eSOLVE_CONTACT on the pair.
@see PxRigidBodyFlag::eENABLE_CCD
@see PxSceneFlag::eENABLE_CCD
*/
eDETECT_CCD_CONTACT = (1<<11),
/**
\brief Provide pre solver velocities in contact reports for this collision pair.
If the collision pair has contact reports enabled, the velocities of the rigid bodies before contacts have been solved
will be provided in the contact report callback unless the pair lost touch in which case no data will be provided.
\note Usually it is not necessary to request these velocities as they will be available by querying the velocity from the provided
PxRigidActor object directly. However, it might be the case that the velocity of a rigid body gets set while the simulation is running
in which case the PxRigidActor would return this new velocity in the contact report callback and not the velocity the simulation used.
@see PxSimulationEventCallback.onContact(), PxContactPairVelocity, PxContactPairHeader.extraDataStream
*/
ePRE_SOLVER_VELOCITY = (1<<12),
/**
\brief Provide post solver velocities in contact reports for this collision pair.
If the collision pair has contact reports enabled, the velocities of the rigid bodies after contacts have been solved
will be provided in the contact report callback unless the pair lost touch in which case no data will be provided.
@see PxSimulationEventCallback.onContact(), PxContactPairVelocity, PxContactPairHeader.extraDataStream
*/
ePOST_SOLVER_VELOCITY = (1<<13),
/**
\brief Provide rigid body poses in contact reports for this collision pair.
If the collision pair has contact reports enabled, the rigid body poses at the contact event will be provided
in the contact report callback unless the pair lost touch in which case no data will be provided.
\note Usually it is not necessary to request these poses as they will be available by querying the pose from the provided
PxRigidActor object directly. However, it might be the case that the pose of a rigid body gets set while the simulation is running
in which case the PxRigidActor would return this new pose in the contact report callback and not the pose the simulation used.
Another use case is related to CCD with multiple passes enabled, A fast moving object might bounce on and off the same
object multiple times. This flag can be used to request the rigid body poses at the time of impact for each such collision event.
@see PxSimulationEventCallback.onContact(), PxContactPairPose, PxContactPairHeader.extraDataStream
*/
eCONTACT_EVENT_POSE = (1<<14),
eNEXT_FREE = (1<<15), //!< For internal use only.
/**
\brief Provided default flag to do simple contact processing for this collision pair.
*/
eCONTACT_DEFAULT = eSOLVE_CONTACT | eDETECT_DISCRETE_CONTACT,
/**
\brief Provided default flag to get commonly used trigger behavior for this collision pair.
*/
eTRIGGER_DEFAULT = eNOTIFY_TOUCH_FOUND | eNOTIFY_TOUCH_LOST | eDETECT_DISCRETE_CONTACT
};
};
/**
\brief Bitfield that contains a set of raised flags defined in PxPairFlag.
@see PxPairFlag
*/
typedef PxFlags<PxPairFlag::Enum, PxU16> PxPairFlags;
PX_FLAGS_OPERATORS(PxPairFlag::Enum, PxU16)
/**
\brief Collection of flags describing the filter actions to take for a collision pair.
@see PxFilterFlags PxSimulationFilterShader PxSimulationFilterCallback
*/
struct PxFilterFlag
{
enum Enum
{
/**
\brief Ignore the collision pair as long as the bounding volumes of the pair objects overlap.
Killed pairs will be ignored by the simulation and won't run through the filter again until one
of the following occurs:
\li The bounding volumes of the two objects overlap again (after being separated)
\li The user enforces a re-filtering (see #PxScene::resetFiltering())
@see PxScene::resetFiltering()
*/
eKILL = (1<<0),
/**
\brief Ignore the collision pair as long as the bounding volumes of the pair objects overlap or until filtering relevant data changes for one of the collision objects.
Suppressed pairs will be ignored by the simulation and won't make another filter request until one
of the following occurs:
\li Same conditions as for killed pairs (see #eKILL)
\li The filter data or the filter object attributes change for one of the collision objects
@see PxFilterData PxFilterObjectAttributes
*/
eSUPPRESS = (1<<1),
/**
\brief Invoke the filter callback (#PxSimulationFilterCallback::pairFound()) for this collision pair.
@see PxSimulationFilterCallback
*/
eCALLBACK = (1<<2),
/**
\brief Track this collision pair with the filter callback mechanism.
When the bounding volumes of the collision pair lose contact, the filter callback #PxSimulationFilterCallback::pairLost()
will be invoked. Furthermore, the filter status of the collision pair can be adjusted through #PxSimulationFilterCallback::statusChange()
once per frame (until a pairLost() notification occurs).
@see PxSimulationFilterCallback
*/
eNOTIFY = (1<<3) | eCALLBACK,
/**
\brief Provided default to get standard behavior:
The application configure the pair's collision properties once when bounding volume overlap is found and
doesn't get asked again about that pair until overlap status or filter properties changes, or re-filtering is requested.
No notification is provided when bounding volume overlap is lost
The pair will not be killed or suppressed, so collision detection will be processed
*/
eDEFAULT = 0
};
};
/**
\brief Bitfield that contains a set of raised flags defined in PxFilterFlag.
@see PxFilterFlag
*/
typedef PxFlags<PxFilterFlag::Enum, PxU16> PxFilterFlags;
PX_FLAGS_OPERATORS(PxFilterFlag::Enum, PxU16)
/**
\brief PxFilterData is user-definable data which gets passed into the collision filtering shader and/or callback.
@see PxShape.setSimulationFilterData() PxShape.getSimulationFilterData() PxSimulationFilterShader PxSimulationFilterCallback
*/
struct PxFilterData
{
//= ATTENTION! =====================================================================================
// Changing the data layout of this class breaks the binary serialization format. See comments for
// PX_BINARY_SERIAL_VERSION. If a modification is required, please adjust the getBinaryMetaData
// function. If the modification is made on a custom branch, please change PX_BINARY_SERIAL_VERSION
// accordingly.
//==================================================================================================
PX_INLINE PxFilterData(const PxEMPTY)
{
}
/**
\brief Default constructor.
*/
PX_INLINE PxFilterData()
{
word0 = word1 = word2 = word3 = 0;
}
/**
\brief Copy constructor.
*/
PX_INLINE PxFilterData(const PxFilterData& fd) : word0(fd.word0), word1(fd.word1), word2(fd.word2), word3(fd.word3) {}
/**
\brief Constructor to set filter data initially.
*/
PX_INLINE PxFilterData(PxU32 w0, PxU32 w1, PxU32 w2, PxU32 w3) : word0(w0), word1(w1), word2(w2), word3(w3) {}
/**
\brief (re)sets the structure to the default.
*/
PX_INLINE void setToDefault()
{
*this = PxFilterData();
}
/**
\brief Assignment operator
*/
PX_INLINE void operator = (const PxFilterData& fd)
{
word0 = fd.word0;
word1 = fd.word1;
word2 = fd.word2;
word3 = fd.word3;
}
/**
\brief Comparison operator to allow use in Array.
*/
PX_INLINE bool operator == (const PxFilterData& a) const
{
return a.word0 == word0 && a.word1 == word1 && a.word2 == word2 && a.word3 == word3;
}
/**
\brief Comparison operator to allow use in Array.
*/
PX_INLINE bool operator != (const PxFilterData& a) const
{
return !(a == *this);
}
PxU32 word0;
PxU32 word1;
PxU32 word2;
PxU32 word3;
};
/**
\brief Identifies each type of filter object.
@see PxGetFilterObjectType()
*/
struct PxFilterObjectType
{
enum Enum
{
/**
\brief A static rigid body
@see PxRigidStatic
*/
eRIGID_STATIC,
/**
\brief A dynamic rigid body
@see PxRigidDynamic
*/
eRIGID_DYNAMIC,
/**
\brief An articulation
@see PxArticulation
*/
eARTICULATION,
//brief internal use only!
eMAX_TYPE_COUNT = 16,
//brief internal use only!
eUNDEFINED = eMAX_TYPE_COUNT-1
};
};
// For internal use only
struct PxFilterObjectFlag
{
enum Enum
{
eKINEMATIC = (1<<4),
eTRIGGER = (1<<5)
};
};
/**
\brief Structure which gets passed into the collision filtering shader and/or callback providing additional information on objects of a collision pair
@see PxSimulationFilterShader PxSimulationFilterCallback getActorType() PxFilterObjectIsKinematic() PxFilterObjectIsTrigger()
*/
typedef PxU32 PxFilterObjectAttributes;
/**
\brief Extract filter object type from the filter attributes of a collision pair object
\param[in] attr The filter attribute of a collision pair object
\return The type of the collision pair object.
@see PxFilterObjectType
*/
PX_INLINE PxFilterObjectType::Enum PxGetFilterObjectType(PxFilterObjectAttributes attr)
{
return PxFilterObjectType::Enum(attr & (PxFilterObjectType::eMAX_TYPE_COUNT-1));
}
/**
\brief Specifies whether the collision object belongs to a kinematic rigid body
\param[in] attr The filter attribute of a collision pair object
\return True if the object belongs to a kinematic rigid body, else false
@see PxRigidBodyFlag::eKINEMATIC
*/
PX_INLINE bool PxFilterObjectIsKinematic(PxFilterObjectAttributes attr)
{
return (attr & PxFilterObjectFlag::eKINEMATIC) != 0;
}
/**
\brief Specifies whether the collision object is a trigger shape
\param[in] attr The filter attribute of a collision pair object
\return True if the object is a trigger shape, else false
@see PxShapeFlag::eTRIGGER_SHAPE
*/
PX_INLINE bool PxFilterObjectIsTrigger(PxFilterObjectAttributes attr)
{
return (attr & PxFilterObjectFlag::eTRIGGER) != 0;
}
/**
\brief Filter shader to specify handling of collision pairs.
Collision filtering is a mechanism to specify how a pair of potentially colliding objects should be processed by the
simulation. A pair of objects is potentially colliding if the bounding volumes of the two objects overlap.
In short, a collision filter decides whether a collision pair should get processed, temporarily ignored or discarded.
If a collision pair should get processed, the filter can additionally specify how it should get processed, for instance,
whether contacts should get resolved, which callbacks should get invoked or which reports should be sent etc.
\note A default implementation of a filter shader is provided in the PhysX extensions library, see #PxDefaultSimulationFilterShader.
@see PxSceneDesc.filterShader PxSimulationFilterCallback
*/
/**
\brief Filter method to specify how a pair of potentially colliding objects should be processed.
Return the PxFilterFlag flags and set the PxPairFlag flags to define what the simulation should do with the given collision pair.
This methods gets called when:
\li The bounding volumes of two objects start to overlap.
\li The bounding volumes of two objects overlap and the filter data or filter attributes of one of the objects changed
\li A re-filtering was forced through resetFiltering() (see #PxScene::resetFiltering())
\li Filtering is requested in scene queries
\note Certain pairs of objects are always ignored and this method does not get called. This is the case for the
following pairs:
\li Pair of static rigid actors
\li A static rigid actor and a kinematic actor (unless one is a trigger or if explicitly enabled through PxSceneFlag::eENABLE_KINEMATIC_STATIC_PAIRS)
\li Two kinematic actors (unless one is a trigger or if explicitly enabled through PxSceneFlag::eENABLE_KINEMATIC_PAIRS)
\li Two jointed rigid bodies and the joint was defined to disable collision
\li Two articulation links if connected through an articulation joint
\note This is a performance critical method and should be stateless. You should neither access external objects
from within this method nor should you call external methods that are not inlined. If you need a more complex
logic to filter a collision pair then use the filter callback mechanism for this pair (see #PxSimulationFilterCallback,
#PxFilterFlag::eCALLBACK, #PxFilterFlag::eNOTIFY).
\param[in] attributes0 The filter attribute of the first object
\param[in] filterData0 The custom filter data of the first object
\param[in] attributes1 The filter attribute of the second object
\param[in] filterData1 The custom filter data of the second object
\param[out] pairFlags Flags giving additional information on how an accepted pair should get processed
\param[in] constantBlock The constant global filter data (see #PxSceneDesc.filterShaderData)
\param[in] constantBlockSize Size of the global filter data (see #PxSceneDesc.filterShaderDataSize)
\return Filter flags defining whether the pair should be discarded, temporarily ignored, processed and whether the
filter callback should get invoked for this pair.
@see PxSimulationFilterCallback PxFilterData PxFilterObjectAttributes PxFilterFlag PxFilterFlags PxPairFlag PxPairFlags
*/
typedef PxFilterFlags (*PxSimulationFilterShader)
(PxFilterObjectAttributes attributes0, PxFilterData filterData0,
PxFilterObjectAttributes attributes1, PxFilterData filterData1,
PxPairFlags& pairFlags, const void* constantBlock, PxU32 constantBlockSize);
/**
\brief Filter callback to specify handling of collision pairs.
This class is provided to implement more complex and flexible collision pair filtering logic, for instance, taking
the state of the user application into account. Filter callbacks also give the user the opportunity to track collision
pairs and update their filter state.
You might want to check the documentation on #PxSimulationFilterShader as well since it includes more general information
on filtering.
\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.
\note The callbacks may execute in user threads or simulation threads, possibly simultaneously. The corresponding objects
may have been deleted by the application earlier in the frame. It is the application's responsibility to prevent race conditions
arising from using the SDK API in the callback while an application thread is making write calls to the scene, and to ensure that
the callbacks are thread-safe. Return values which depend on when the callback is called during the frame will introduce nondeterminism
into the simulation.
@see PxSceneDesc.filterCallback PxSimulationFilterShader
*/
class PxSimulationFilterCallback
{
public:
/**
\brief Filter method to specify how a pair of potentially colliding objects should be processed.
This method gets called when the filter flags returned by the filter shader (see #PxSimulationFilterShader)
indicate that the filter callback should be invoked (#PxFilterFlag::eCALLBACK or #PxFilterFlag::eNOTIFY set).
Return the PxFilterFlag flags and set the PxPairFlag flags to define what the simulation should do with the given
collision pair.
\param[in] pairID Unique ID of the collision pair used to issue filter status changes for the pair (see #statusChange())
\param[in] attributes0 The filter attribute of the first object
\param[in] filterData0 The custom filter data of the first object
\param[in] a0 Actor pointer of the first object
\param[in] s0 Shape pointer of the first object (NULL if the object has no shapes)
\param[in] attributes1 The filter attribute of the second object
\param[in] filterData1 The custom filter data of the second object
\param[in] a1 Actor pointer of the second object
\param[in] s1 Shape pointer of the second object (NULL if the object has no shapes)
\param[in,out] pairFlags In: Pair flags returned by the filter shader. Out: Additional information on how an accepted pair should get processed
\return Filter flags defining whether the pair should be discarded, temporarily ignored or processed and whether the pair
should be tracked and send a report on pair deletion through the filter callback
@see PxSimulationFilterShader PxFilterData PxFilterObjectAttributes PxFilterFlag PxPairFlag
*/
virtual PxFilterFlags pairFound( PxU32 pairID,
PxFilterObjectAttributes attributes0, PxFilterData filterData0, const PxActor* a0, const PxShape* s0,
PxFilterObjectAttributes attributes1, PxFilterData filterData1, const PxActor* a1, const PxShape* s1,
PxPairFlags& pairFlags) = 0;
/**
\brief Callback to inform that a tracked collision pair is gone.
This method gets called when a collision pair disappears or gets re-filtered. Only applies to
collision pairs which have been marked as filter callback pairs (#PxFilterFlag::eNOTIFY set in #pairFound()).
\param[in] pairID Unique ID of the collision pair that disappeared
\param[in] attributes0 The filter attribute of the first object
\param[in] filterData0 The custom filter data of the first object
\param[in] attributes1 The filter attribute of the second object
\param[in] filterData1 The custom filter data of the second object
\param[in] objectRemoved True if the pair was lost because one of the objects got removed from the scene
@see pairFound() PxSimulationFilterShader PxFilterData PxFilterObjectAttributes
*/
virtual void pairLost( PxU32 pairID,
PxFilterObjectAttributes attributes0,
PxFilterData filterData0,
PxFilterObjectAttributes attributes1,
PxFilterData filterData1,
bool objectRemoved) = 0;
/**
\brief Callback to give the opportunity to change the filter state of a tracked collision pair.
This method gets called once per simulation step to let the application change the filter and pair
flags of a collision pair that has been reported in #pairFound() and requested callbacks by
setting #PxFilterFlag::eNOTIFY. To request a change of filter status, the target pair has to be
specified by its ID, the new filter and pair flags have to be provided and the method should return true.
\note If this method changes the filter status of a collision pair and the pair should keep being tracked
by the filter callbacks then #PxFilterFlag::eNOTIFY has to be set.
\note The application is responsible to ensure that this method does not get called for pairs that have been
reported as lost, see #pairLost().
\param[out] pairID ID of the collision pair for which the filter status should be changed
\param[out] pairFlags The new pairFlags to apply to the collision pair
\param[out] filterFlags The new filterFlags to apply to the collision pair
\return True if the changes should be applied. In this case the method will get called again. False if
no more status changes should be done in the current simulation step. In that case the provided flags will be discarded.
@see pairFound() pairLost() PxFilterFlag PxPairFlag
*/
virtual bool statusChange(PxU32& pairID, PxPairFlags& pairFlags, PxFilterFlags& filterFlags) = 0;
protected:
virtual ~PxSimulationFilterCallback() {}
};
struct PxPairFilteringMode
{
enum Enum
{
/**
Output pair from BP, potentially send to user callbacks, create regular interaction object.
Similar to enabling PxSceneFlag::eENABLE_KINEMATIC_STATIC_PAIRS / PxSceneFlag::eENABLE_KINEMATIC_PAIRS.
*/
eKEEP,
/**
Output pair from BP, create interaction marker. Can be later switched to regular interaction.
Similar to disabling PxSceneFlag::eENABLE_KINEMATIC_STATIC_PAIRS / PxSceneFlag::eENABLE_KINEMATIC_PAIRS.
*/
eSUPPRESS,
/**
Don't output pair from BP. Cannot be later switched to regular interaction, needs "resetFiltering" call.
*/
eKILL,
/**
Default is to ignore the mode and use PxSceneFlag::eENABLE_KINEMATIC_STATIC_PAIRS and PxSceneFlag::eENABLE_KINEMATIC_PAIRS instead (compatibility).
*/
eDEFAULT
};
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,66 @@
//
// 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-2018 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_FORCE_MODE
#define PX_PHYSICS_NX_FORCE_MODE
#include "foundation/PxPreprocessor.h"
/** \addtogroup physics
@{
*/
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Parameter to addForce() and addTorque() calls, determines the exact operation that is carried out.
@see PxRigidBody.addForce() PxRigidBody.addTorque()
*/
struct PxForceMode
{
enum Enum
{
eFORCE, //!< parameter has unit of mass * distance/ time^2, i.e. a force
eIMPULSE, //!< parameter has unit of mass * distance /time
eVELOCITY_CHANGE, //!< parameter has unit of distance / time, i.e. the effect is mass independent: a velocity change.
eACCELERATION //!< parameter has unit of distance/ time^2, i.e. an acceleration. It gets treated just like a force except the mass is not divided out before integration.
};
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,158 @@
//
// 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-2018 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_FOUNDATION_PX_FOUNDATION_H
#define PX_FOUNDATION_PX_FOUNDATION_H
/** \addtogroup foundation
@{
*/
#include "foundation/Px.h"
#include "foundation/PxErrors.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Foundation SDK singleton class.
You need to have an instance of this class to instance the higher level SDKs.
*/
class PX_FOUNDATION_API PxFoundation
{
public:
/**
\brief Destroys the instance it is called on.
The operation will fail, if there are still modules referencing the foundation object. Release all dependent modules
prior
to calling this method.
@see PxCreateFoundation()
*/
virtual void release() = 0;
/**
retrieves error callback
*/
virtual PxErrorCallback& getErrorCallback() = 0;
/**
Sets mask of errors to report.
*/
virtual void setErrorLevel(PxErrorCode::Enum mask = PxErrorCode::eMASK_ALL) = 0;
/**
Retrieves mask of errors to be reported.
*/
virtual PxErrorCode::Enum getErrorLevel() const = 0;
/**
Retrieves the allocator this object was created with.
*/
virtual PxAllocatorCallback& getAllocatorCallback() = 0;
/**
Retrieves if allocation names are being passed to allocator callback.
*/
virtual bool getReportAllocationNames() const = 0;
/**
Set if allocation names are being passed to allocator callback.
\details Enabled by default in debug and checked build, disabled by default in profile and release build.
*/
virtual void setReportAllocationNames(bool value) = 0;
protected:
virtual ~PxFoundation()
{
}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/**
\brief Creates an instance of the foundation class
The foundation class is needed to initialize higher level SDKs. There may be only one instance per process.
Calling this method after an instance has been created already will result in an error message and NULL will be
returned.
\param version Version number we are expecting (should be #PX_PHYSICS_VERSION)
\param allocator User supplied interface for allocating memory(see #PxAllocatorCallback)
\param errorCallback User supplied interface for reporting errors and displaying messages(see #PxErrorCallback)
\return Foundation instance on success, NULL if operation failed
@see PxFoundation
*/
PX_C_EXPORT PX_FOUNDATION_API physx::PxFoundation* PX_CALL_CONV
PxCreateFoundation(physx::PxU32 version, physx::PxAllocatorCallback& allocator, physx::PxErrorCallback& errorCallback);
/**
\brief Retrieves the Foundation SDK after it has been created.
\note The behavior of this method is undefined if the foundation instance has not been created already.
@see PxCreateFoundation()
*/
#if PX_CLANG
#if PX_LINUX
#pragma clang diagnostic push
#pragma clang diagnostic ignored "-Wreturn-type-c-linkage"
#endif // PX_LINUX
#endif // PX_CLANG
PX_C_EXPORT PX_FOUNDATION_API physx::PxFoundation& PX_CALL_CONV PxGetFoundation();
#if PX_CLANG
#if PX_LINUX
#pragma clang diagnostic pop
#endif // PX_LINUX
#endif // PX_CLANG
namespace physx
{
class PxProfilerCallback;
}
/**
\brief Get the callback that will be used for all profiling.
*/
PX_C_EXPORT PX_FOUNDATION_API physx::PxProfilerCallback* PX_CALL_CONV PxGetProfilerCallback();
/**
\brief Set the callback that will be used for all profiling.
*/
PX_C_EXPORT PX_FOUNDATION_API void PX_CALL_CONV PxSetProfilerCallback(physx::PxProfilerCallback* profiler);
/** @} */
#endif // PX_FOUNDATION_PX_FOUNDATION_H

View File

@ -0,0 +1,228 @@
//
// 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-2018 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_IMMEDIATE_MODE
#define PX_PHYSICS_IMMEDIATE_MODE
/** \addtogroup immediatemode
@{ */
#include "PxPhysXConfig.h"
#include "solver/PxSolverDefs.h"
#include "collision/PxCollisionDefs.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
#if !PX_DOXYGEN
namespace immediate
{
#endif
/**
\brief Structure to store rigid body properties
*/
struct PxRigidBodyData
{
PX_ALIGN(16, PxVec3 linearVelocity); //!< 12 Linear velocity
PxReal invMass; //!< 16 Inverse mass
PxVec3 angularVelocity; //!< 28 Angular velocity
PxReal maxDepenetrationVelocity; //!< 32 Maximum de-penetration velocity
PxVec3 invInertia; //!< 44 Mass-space inverse interia diagonal vector
PxReal maxContactImpulse; //!< 48 Maximum permissable contact impulse
PxTransform body2World; //!< 76 World space transform
PxReal linearDamping; //!< 80 Linear damping coefficient
PxReal angularDamping; //!< 84 Angular damping coefficient
PxReal maxLinearVelocitySq; //!< 88 Squared maximum linear velocity
PxReal maxAngularVelocitySq; //!< 92 Squared maximum angular velocity
PxU32 pad; //!< 96 Padding for 16-byte alignment
};
/**
\brief Callback class to record contact points produced by immediate::PxGenerateContacts
*/
class PxContactRecorder
{
public:
/**
\brief Method to record new contacts
\param[in] contactPoints The contact points produced
\param[in] nbContacts The number of contact points produced
\param[in] index The index of this pair. This is an index from 0-N-1 identifying which pair this relates to from within the array of pairs passed to PxGenerateContacts
\return a boolean to indicate if this callback successfully stored the contacts or not.
*/
virtual bool recordContacts(const Gu::ContactPoint* contactPoints, const PxU32 nbContacts, const PxU32 index) = 0;
virtual ~PxContactRecorder(){}
};
/**
\brief Constructs a PxSolverBodyData structure based on rigid body properties. Applies gravity, damping and clamps maximum velocity.
\param[in] inRigidData The array rigid body properties
\param[out] outSolverBodyData The array of solverBodyData produced to repreent these bodies
\param[in] nbBodies The total number of solver bodies to create
\param[in] gravity The gravity vector
\param[in] dt The timestep
*/
PX_C_EXPORT PX_PHYSX_CORE_API void PxConstructSolverBodies(const PxRigidBodyData* inRigidData, PxSolverBodyData* outSolverBodyData, const PxU32 nbBodies, const PxVec3& gravity, const PxReal dt);
/**
\brief Constructs a PxSolverBodyData structure for a static body at a given pose.
\param[in] globalPose The pose of this static actor
\param[out] solverBodyData The solver body representation of this static actor
*/
PX_C_EXPORT PX_PHYSX_CORE_API void PxConstructStaticSolverBody(const PxTransform& globalPose,PxSolverBodyData& solverBodyData);
/**
\brief Groups together sets of independent PxSolverConstraintDesc objects to be solved using SIMD SOA approach.
\param[in] solverConstraintDescs the set of solver constraint descs to batch
\param[in] nbConstraints The number of constraints to batch
\param[in,out] solverBodies The array of solver bodies that the constraints reference. Some fields in these structures are written to as scratch memory for the batching.
\param[in] nbBodies The number of bodies
\param[out] outBatchHeaders The batch headers produced by this batching process. This array must have at least 1 entry per input constraint
\param[out] outOrderedConstraintDescs A reordered copy of the constraint descs. This array is referenced by the constraint batches. This array must have at least 1 entry per input constraint.
\return The total number of batches produced. This should be less than or equal to nbConstraints.
\note This method considers all bodies within the range [0, nbBodies-1] to be valid dynamic bodies. A given dynamic body can only be referenced in a batch once. Static or kinematic bodies can be
referenced multiple times within a batch safely because constraints do not affect their velocities. The batching will implicitly consider any bodies outside of the range [0, nbBodies-1] to be
infinite mass (static or kinematic). This means that either appending static/kinematic to the end of the array of bodies or placing static/kinematic bodies at before the start body pointer
will ensure that the minimum number of batches are produced.
*/
PX_C_EXPORT PX_PHYSX_CORE_API PxU32 PxBatchConstraints(PxSolverConstraintDesc* solverConstraintDescs, const PxU32 nbConstraints, PxSolverBody* solverBodies, PxU32 nbBodies, PxConstraintBatchHeader* outBatchHeaders,
PxSolverConstraintDesc* outOrderedConstraintDescs);
/**
\brief Creates a set of contact constraint blocks. Note that, depending the results of PxBatchConstraints, each batchHeader may refer to up to 4 solverConstraintDescs.
This function will allocate both constraint and friction patch data via the PxConstraintAllocator provided. Constraint data is only valid until PxSolveConstraints has completed.
Friction data is to be retained and provided by the application for friction correlation.
\param[in] batchHeader Array of batch headers to process
\param[in] nbHeaders The total number of headers
\param[in] contactDescs An array of contact descs defining the pair and contact properties of each respective contacting pair
\param[in] allocator An allocator callback to allocate constraint and friction memory
\param[in] invDt The inverse timestep
\param[in] bounceThreshold The bounce threshold. Relative velocities below this will be solved by bias only. Relative velocities above this will be solved by restitution. If restitution is zero
then these pairs will always be solved by bias.
\param[in] frictionOffsetThreshold The friction offset threshold. Contacts whose separations are below this threshold can generate friction constraints.
\param[in] correlationDistance The correlation distance used by friction correlation to identify whether a friction patch is broken on the grounds of relation separation.
\return a boolean to define if this method was successful or not.
*/
PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateContactConstraints(PxConstraintBatchHeader* batchHeader, const PxU32 nbHeaders, PxSolverContactDesc* contactDescs,
PxConstraintAllocator& allocator, PxReal invDt, PxReal bounceThreshold, PxReal frictionOffsetThreshold, PxReal correlationDistance);
/**
\brief Creates a set of joint constraint blocks. Note that, depending the results of PxBatchConstraints, the batchHeader may refer to up to 4 solverConstraintDescs
\param[in] batchHeader The array of batch headers to be processed
\param[in] nbHeaders The total number of batch headers to process
\param[in] jointDescs An array of constraint prep descs defining the properties of the constraints being created
\param[in] allocator An allocator callback to allocate constraint data
\param[in] dt The timestep
\param[in] invDt The inverse timestep
\return a boolean indicating if this method was successful or not.
*/
PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateJointConstraints(PxConstraintBatchHeader* batchHeader, const PxU32 nbHeaders, PxSolverConstraintPrepDesc* jointDescs, PxConstraintAllocator& allocator, PxReal dt, PxReal invDt);
/**
\brief Creates a set of joint constraint blocks. This function runs joint shaders defined inside PxConstraint** param, fills in joint row information in jointDescs and then calls PxCreateJointConstraints.
\param[in] batchHeader The set of batchHeaders to be processed
\param[in] nbBatchHeaders The number of batch headers to process.
\param[in] constraints The set of constraints to be used to produce constraint rows
\param[in,out] jointDescs An array of constraint prep descs defining the properties of the constraints being created
\param[in] allocator An allocator callback to allocate constraint data
\param[in] dt The timestep
\param[in] invDt The inverse timestep
\return a boolean indicating if this method was successful or not.
*/
PX_C_EXPORT PX_PHYSX_CORE_API bool PxCreateJointConstraintsWithShaders(PxConstraintBatchHeader* batchHeader, const PxU32 nbBatchHeaders, PxConstraint** constraints, PxSolverConstraintPrepDesc* jointDescs, PxConstraintAllocator& allocator, PxReal dt, PxReal invDt);
/**
\brief Iteratively solves the set of constraints defined by the provided PxConstraintBatchHeader and PxSolverConstraintDesc structures. Updates deltaVelocities inside the PxSolverBody structures. Produces resulting linear and angular motion velocities.
\param[in] batchHeaders The set of batch headers to be solved
\param[in] nbBatchHeaders The total number of batch headers to be solved
\param[in] solverConstraintDescs The reordererd set of solver constraint descs referenced by the batch headers
\param[in,out] solverBodies The set of solver bodies the bodies reference
\param[out] linearMotionVelocity The resulting linear motion velocity
\param[out] angularMotionVelocity The resulting angular motion velocity.
\param[in] nbSolverBodies The total number of solver bodies
\param[in] nbPositionIterations The number of position iterations to run
\param[in] nbVelocityIterations The number of velocity iterations to run
*/
PX_C_EXPORT PX_PHYSX_CORE_API void PxSolveConstraints(PxConstraintBatchHeader* batchHeaders, const PxU32 nbBatchHeaders, PxSolverConstraintDesc* solverConstraintDescs, PxSolverBody* solverBodies,
PxVec3* linearMotionVelocity, PxVec3* angularMotionVelocity, const PxU32 nbSolverBodies, const PxU32 nbPositionIterations, const PxU32 nbVelocityIterations);
/**
\brief Integrates a rigid body, returning the new velocities and transforms. After this function has been called, solverBodyData stores all the body's velocity data.
\param[in,out] solverBodyData The array of solver body data to be integrated
\param[in] solverBody The bodies' linear and angular velocities
\param[in] linearMotionVelocity The bodies' linear motion velocity array
\param[in] angularMotionState The bodies' angular motion velocity array
\param[in] nbBodiesToIntegrate The total number of bodies to integrate
\param[in] dt The timestep
*/
PX_C_EXPORT PX_PHYSX_CORE_API void PxIntegrateSolverBodies(PxSolverBodyData* solverBodyData, PxSolverBody* solverBody, const PxVec3* linearMotionVelocity, const PxVec3* angularMotionState, const PxU32 nbBodiesToIntegrate, PxReal dt);
/**
abrief Performs contact generation for a given pair of geometries at the specified poses. Produced contacts are stored in the provided Gu::ContactBuffer. Information is cached in PxCache structure
to accelerate future contact generation between pairs. This cache data is valid only as long as the memory provided by PxCacheAllocator has not been released/re-used. Recommendation is to
retain that data for a single simulation frame, discarding cached data after 2 frames. If the cached memory has been released/re-used prior to the corresponding pair having contact generation
performed again, it is the application's responsibility to reset the PxCache.
\param[in] geom0 Array of geometries to perform collision detection on.
\param[in] geom1 Array of geometries to perform collision detection on
\param[in] pose0 Array of poses associated with the corresponding entry in the geom0 array
\param[in] pose1 Array of poses associated with the corresponding entry in the geom1 array
\param[in,out] contactCache Array of contact caches associated with each pair geom0[i] + geom1[i]
\param[in] nbPairs The total number of pairs to process
\param[in] contactRecorder A callback that is called to record contacts for each pair that detects contacts
\param[in] contactDistance The distance at which contacts begin to be generated between the pairs
\param[in] meshContactMargin The mesh contact margin.
\param[in] toleranceLength The toleranceLength. Used for scaling distance-based thresholds internally to produce appropriate results given simulations in different units
\param[in] allocator A callback to allocate memory for the contact cache
\return a boolean indicating if the function was successful or not.
*/
PX_C_EXPORT PX_PHYSX_CORE_API bool PxGenerateContacts(const PxGeometry* const * geom0, const PxGeometry* const * geom1, const PxTransform* pose0, const PxTransform* pose1, PxCache* contactCache, const PxU32 nbPairs, PxContactRecorder& contactRecorder,
const PxReal contactDistance, const PxReal meshContactMargin, const PxReal toleranceLength, PxCacheAllocator& allocator);
#if !PX_DOXYGEN
}
#endif
#if !PX_DOXYGEN
}
#endif
/** @} */
#endif

View File

@ -0,0 +1,93 @@
//
// 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-2018 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_LOCKED_DATA
#define PX_PHYSICS_NX_LOCKED_DATA
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "foundation/PxFlags.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
struct PxDataAccessFlag
{
enum Enum
{
eREADABLE = (1 << 0),
eWRITABLE = (1 << 1),
eDEVICE = (1 << 2)
};
};
/**
\brief collection of set bits defined in PxDataAccessFlag.
@see PxDataAccessFlag
*/
typedef PxFlags<PxDataAccessFlag::Enum,PxU8> PxDataAccessFlags;
PX_FLAGS_OPERATORS(PxDataAccessFlag::Enum,PxU8)
/**
\brief Parent class for bulk data that is shared between the SDK and the application.
*/
class PxLockedData
{
public:
/**
\brief Any combination of PxDataAccessFlag::eREADABLE and PxDataAccessFlag::eWRITABLE
@see PxDataAccessFlag
*/
virtual PxDataAccessFlags getDataAccessFlags() = 0;
/**
\brief Unlocks the bulk data.
*/
virtual void unlock() = 0;
/**
\brief virtual destructor
*/
virtual ~PxLockedData() {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,324 @@
//
// 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-2018 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_NXMATERIAL
#define PX_PHYSICS_NXMATERIAL
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "common/PxBase.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxScene;
/**
\brief Flags which control the behavior of a material.
@see PxMaterial
*/
struct PxMaterialFlag
{
enum Enum
{
/**
If this flag is set, friction computations are always skipped between shapes with this material and any other shape.
*/
eDISABLE_FRICTION = 1 << 0,
/**
The difference between "normal" and "strong" friction is that the strong friction feature
remembers the "friction error" between simulation steps. The friction is a force trying to
hold objects in place (or slow them down) and this is handled in the solver. But since the
solver is only an approximation, the result of the friction calculation can include a small
"error" - e.g. a box resting on a slope should not move at all if the static friction is in
action, but could slowly glide down the slope because of a small friction error in each
simulation step. The strong friction counter-acts this by remembering the small error and
taking it to account during the next simulation step.
However, in some cases the strong friction could cause problems, and this is why it is
possible to disable the strong friction feature by setting this flag. One example is
raycast vehicles, that are sliding fast across the surface, but still need a precise
steering behavior. It may be a good idea to reenable the strong friction when objects
are coming to a rest, to prevent them from slowly creeping down inclines.
Note: This flag only has an effect if the PxMaterialFlag::eDISABLE_FRICTION bit is 0.
*/
eDISABLE_STRONG_FRICTION = 1 << 1
};
};
/**
\brief collection of set bits defined in PxMaterialFlag.
@see PxMaterialFlag
*/
typedef PxFlags<PxMaterialFlag::Enum,PxU16> PxMaterialFlags;
PX_FLAGS_OPERATORS(PxMaterialFlag::Enum,PxU16)
/**
\brief enumeration that determines the way in which two material properties will be combined to yield a friction or restitution coefficient for a collision.
When two actors come in contact with each other, they each have materials with various coefficients, but we only need a single set of coefficients for the pair.
Physics doesn't have any inherent combinations because the coefficients are determined empirically on a case by case
basis. However, simulating this with a pairwise lookup table is often impractical.
For this reason the following combine behaviors are available:
eAVERAGE
eMIN
eMULTIPLY
eMAX
The effective combine mode for the pair is maximum(material0.combineMode, material1.combineMode).
@see PxMaterial.setFrictionCombineMode() PxMaterial.getFrictionCombineMode() PxMaterial.setRestitutionCombineMode() PxMaterial.getFrictionCombineMode()
*/
struct PxCombineMode
{
enum Enum
{
eAVERAGE = 0, //!< Average: (a + b)/2
eMIN = 1, //!< Minimum: minimum(a,b)
eMULTIPLY = 2, //!< Multiply: a*b
eMAX = 3, //!< Maximum: maximum(a,b)
eN_VALUES = 4, //!< This is not a valid combine mode, it is a sentinel to denote the number of possible values. We assert that the variable's value is smaller than this.
ePAD_32 = 0x7fffffff //!< This is not a valid combine mode, it is to assure that the size of the enum type is big enough.
};
};
/**
\brief Material class to represent a set of surface properties.
@see PxPhysics.createMaterial
*/
class PxMaterial : public PxBase
{
public:
/**
\brief Decrements the reference count of a material and releases it if the new reference count is zero.
@see PxPhysics.createMaterial()
*/
virtual void release() = 0;
/**
\brief Returns the reference count of the material.
At creation, the reference count of the material is 1. Every shape referencing this material increments the
count by 1. When the reference count reaches 0, and only then, the material gets destroyed automatically.
\return the current reference count.
*/
virtual PxU32 getReferenceCount() const = 0;
/**
\brief Acquires a counted reference to a material.
This method increases the reference count of the material by 1. Decrement the reference count by calling release()
*/
virtual void acquireReference() = 0;
/**
\brief Sets the coefficient of dynamic friction.
The coefficient of dynamic friction should be in [0, PX_MAX_F32). If set to greater than staticFriction, the effective value of staticFriction will be increased to match.
<b>Sleeping:</b> Does <b>NOT</b> wake any actors which may be affected.
\param[in] coef Coefficient of dynamic friction. <b>Range:</b> [0, PX_MAX_F32)
@see getDynamicFriction()
*/
virtual void setDynamicFriction(PxReal coef) = 0;
/**
\brief Retrieves the DynamicFriction value.
\return The coefficient of dynamic friction.
@see setDynamicFriction
*/
virtual PxReal getDynamicFriction() const = 0;
/**
\brief Sets the coefficient of static friction
The coefficient of static friction should be in the range [0, PX_MAX_F32)
<b>Sleeping:</b> Does <b>NOT</b> wake any actors which may be affected.
\param[in] coef Coefficient of static friction. <b>Range:</b> [0, PX_MAX_F32)
@see getStaticFriction()
*/
virtual void setStaticFriction(PxReal coef) = 0;
/**
\brief Retrieves the coefficient of static friction.
\return The coefficient of static friction.
@see setStaticFriction
*/
virtual PxReal getStaticFriction() const = 0;
/**
\brief Sets the coefficient of restitution
A coefficient of 0 makes the object bounce as little as possible, higher values up to 1.0 result in more bounce.
<b>Sleeping:</b> Does <b>NOT</b> wake any actors which may be affected.
\param[in] rest Coefficient of restitution. <b>Range:</b> [0,1]
@see getRestitution()
*/
virtual void setRestitution(PxReal rest) = 0;
/**
\brief Retrieves the coefficient of restitution.
See #setRestitution.
\return The coefficient of restitution.
@see setRestitution()
*/
virtual PxReal getRestitution() const = 0;
/**
\brief Raises or clears a particular material flag.
See the list of flags #PxMaterialFlag
<b>Sleeping:</b> Does <b>NOT</b> wake any actors which may be affected.
\param[in] flag The PxMaterial flag to raise(set) or clear.
@see getFlags() PxMaterialFlag
*/
virtual void setFlag(PxMaterialFlag::Enum flag, bool) = 0;
/**
\brief sets all the material flags.
See the list of flags #PxMaterialFlag
<b>Sleeping:</b> Does <b>NOT</b> wake any actors which may be affected.
*/
virtual void setFlags( PxMaterialFlags inFlags ) = 0;
/**
\brief Retrieves the flags. See #PxMaterialFlag.
\return The material flags.
@see PxMaterialFlag setFlags()
*/
virtual PxMaterialFlags getFlags() const = 0;
/**
\brief Sets the friction combine mode.
See the enum ::PxCombineMode .
<b>Sleeping:</b> Does <b>NOT</b> wake any actors which may be affected.
\param[in] combMode Friction combine mode to set for this material. See #PxCombineMode.
@see PxCombineMode getFrictionCombineMode setStaticFriction() setDynamicFriction()
*/
virtual void setFrictionCombineMode(PxCombineMode::Enum combMode) = 0;
/**
\brief Retrieves the friction combine mode.
See #setFrictionCombineMode.
\return The friction combine mode for this material.
@see PxCombineMode setFrictionCombineMode()
*/
virtual PxCombineMode::Enum getFrictionCombineMode() const = 0;
/**
\brief Sets the restitution combine mode.
See the enum ::PxCombineMode .
<b>Sleeping:</b> Does <b>NOT</b> wake any actors which may be affected.
\param[in] combMode Restitution combine mode for this material. See #PxCombineMode.
@see PxCombineMode getRestitutionCombineMode() setRestitution()
*/
virtual void setRestitutionCombineMode(PxCombineMode::Enum combMode) = 0;
/**
\brief Retrieves the restitution combine mode.
See #setRestitutionCombineMode.
\return The coefficient of restitution combine mode for this material.
@see PxCombineMode setRestitutionCombineMode getRestitution()
*/
virtual PxCombineMode::Enum getRestitutionCombineMode() const = 0;
//public variables:
void* userData; //!< user can assign this to whatever, usually to create a 1:1 relationship with a user object.
virtual const char* getConcreteTypeName() const { return "PxMaterial"; }
protected:
PX_INLINE PxMaterial(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags), userData(NULL) {}
PX_INLINE PxMaterial(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
virtual ~PxMaterial() {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxMaterial", name) || PxBase::isKindOf(name); }
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,78 @@
//
// 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-2018 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
#define PX_PHYSICS_NX
/** Configuration include file for PhysX SDK */
/** \addtogroup physics
@{
*/
#include "common/PxPhysXCommonConfig.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxPhysics;
class PxShape;
class PxActor;
class PxRigidActor;
class PxRigidStatic;
class PxRigidDynamic;
class PxConstraint;
class PxConstraintDesc;
class PxArticulation;
class PxArticulationReducedCoordinate;
class PxArticulationBase;
class PxArticulationLink;
class PxArticulationJoint;
class PxArticulationJointReducedCoordinate;
class PxArticulationJointBase;
class PxMaterial;
class PxScene;
class PxSceneDesc;
class PxTolerancesScale;
class PxAggregate;
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,729 @@
//
// 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-2018 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_PHYSICS
#define PX_PHYSICS_NX_PHYSICS
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "PxDeletionListener.h"
#include "foundation/PxTransform.h"
#include "PxShape.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxPvd;
class PxPhysicsInsertionCallback;
class PxRigidActor;
class PxConstraintConnector;
struct PxConstraintShaderTable;
class PxGeometry;
class PxFoundation;
class PxSerializationRegistry;
class PxPruningStructure;
class PxBVHStructure;
/**
\brief Abstract singleton factory class used for instancing objects in the Physics SDK.
In addition you can use PxPhysics to set global parameters which will effect all scenes and create
objects that can be shared across multiple scenes.
You can get an instance of this class by calling PxCreateBasePhysics() or PxCreatePhysics() with pre-registered modules.
@see PxCreatePhysics() PxCreateBasePhysics() PxScene PxVisualizationParameter
*/
class PxPhysics
{
public:
/** @name Basics
*/
//@{
virtual ~PxPhysics() {}
/**
\brief Destroys the instance it is called on.
Use this release method to destroy an instance of this class. Be sure
to not keep a reference to this object after calling release.
Avoid release calls while a scene is simulating (in between simulate() and fetchResults() calls).
Note that this must be called once for each prior call to PxCreatePhysics, as
there is a reference counter. Also note that you mustn't destroy the allocator or the error callback (if available) until after the
reference count reaches 0 and the SDK is actually removed.
Releasing an SDK will also release any scenes, triangle meshes, convex meshes, heightfields and shapes
created through it, provided the user hasn't already done so.
\note This function is required to be called to release foundation usage.
@see PxCreatePhysics()
*/
virtual void release() = 0;
/**
\brief Retrieves the Foundation instance.
\return A reference to the Foundation object.
*/
virtual PxFoundation& getFoundation() = 0;
/**
\brief Creates an aggregate with the specified maximum size and selfCollision property.
\param [in] maxSize The maximum number of actors that may be placed in the aggregate.
\param [in] enableSelfCollision Whether the aggregate supports self-collision
\return The new aggregate.
@see PxAggregate
*/
virtual PxAggregate* createAggregate(PxU32 maxSize, bool enableSelfCollision) = 0;
/**
\brief Returns the simulation tolerance parameters.
\return The current simulation tolerance parameters.
*/
virtual const PxTolerancesScale& getTolerancesScale() const = 0;
//@}
/** @name Meshes
*/
//@{
/**
\brief Creates a triangle mesh object.
This can then be instanced into #PxShape objects.
\param [in] stream The triangle mesh stream.
\return The new triangle mesh.
@see PxTriangleMesh PxMeshPreprocessingFlag PxTriangleMesh.release() PxInputStream PxTriangleMeshFlag
*/
virtual PxTriangleMesh* createTriangleMesh(PxInputStream& stream) = 0;
/**
\brief Return the number of triangle meshes that currently exist.
\return Number of triangle meshes.
@see getTriangleMeshes()
*/
virtual PxU32 getNbTriangleMeshes() const = 0;
/**
\brief Writes the array of triangle mesh pointers to a user buffer.
Returns the number of pointers written.
The ordering of the triangle meshes in the array is not specified.
\param [out] userBuffer The buffer to receive triangle mesh pointers.
\param [in] bufferSize The number of triangle mesh pointers which can be stored in the buffer.
\param [in] startIndex Index of first mesh pointer to be retrieved
\return The number of triangle mesh pointers written to userBuffer, this should be less or equal to bufferSize.
@see getNbTriangleMeshes() PxTriangleMesh
*/
virtual PxU32 getTriangleMeshes(PxTriangleMesh** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
/**
\brief Creates a heightfield object from previously cooked stream.
This can then be instanced into #PxShape objects.
\param [in] stream The heightfield mesh stream.
\return The new heightfield.
@see PxHeightField PxHeightField.release() PxInputStream PxRegisterHeightFields
*/
virtual PxHeightField* createHeightField(PxInputStream& stream) = 0;
/**
\brief Return the number of heightfields that currently exist.
\return Number of heightfields.
@see getHeightFields()
*/
virtual PxU32 getNbHeightFields() const = 0;
/**
\brief Writes the array of heightfield pointers to a user buffer.
Returns the number of pointers written.
The ordering of the heightfields in the array is not specified.
\param [out] userBuffer The buffer to receive heightfield pointers.
\param [in] bufferSize The number of heightfield pointers which can be stored in the buffer.
\param [in] startIndex Index of first heightfield pointer to be retrieved
\return The number of heightfield pointers written to userBuffer, this should be less or equal to bufferSize.
@see getNbHeightFields() PxHeightField
*/
virtual PxU32 getHeightFields(PxHeightField** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
/**
\brief Creates a convex mesh object.
This can then be instanced into #PxShape objects.
\param [in] stream The stream to load the convex mesh from.
\return The new convex mesh.
@see PxConvexMesh PxConvexMesh.release() PxInputStream createTriangleMesh() PxConvexMeshGeometry PxShape
*/
virtual PxConvexMesh* createConvexMesh(PxInputStream &stream) = 0;
/**
\brief Return the number of convex meshes that currently exist.
\return Number of convex meshes.
@see getConvexMeshes()
*/
virtual PxU32 getNbConvexMeshes() const = 0;
/**
\brief Writes the array of convex mesh pointers to a user buffer.
Returns the number of pointers written.
The ordering of the convex meshes in the array is not specified.
\param [out] userBuffer The buffer to receive convex mesh pointers.
\param [in] bufferSize The number of convex mesh pointers which can be stored in the buffer.
\param [in] startIndex Index of first convex mesh pointer to be retrieved
\return The number of convex mesh pointers written to userBuffer, this should be less or equal to bufferSize.
@see getNbConvexMeshes() PxConvexMesh
*/
virtual PxU32 getConvexMeshes(PxConvexMesh** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
/**
\brief Creates a bounding volume hierarchy structure.
\param [in] stream The stream to load the BVH structure from.
\return The new BVH structure.
@see PxBVHStructure PxInputStream
*/
virtual PxBVHStructure* createBVHStructure(PxInputStream &stream) = 0;
/**
\brief Return the number of bounding volume hierarchy structures that currently exist.
\return Number of bounding volume hierarchy structures.
@see getBVHStructures()
*/
virtual PxU32 getNbBVHStructures() const = 0;
/**
\brief Writes the array of bounding volume hierarchy structure pointers to a user buffer.
Returns the number of pointers written.
The ordering of the BVH structures in the array is not specified.
\param [out] userBuffer The buffer to receive BVH structure pointers.
\param [in] bufferSize The number of BVH structure pointers which can be stored in the buffer.
\param [in] startIndex Index of first BVH structure pointer to be retrieved
\return The number of BVH structure pointers written to userBuffer, this should be less or equal to bufferSize.
@see getNbBVHStructures() PxBVHStructure
*/
virtual PxU32 getBVHStructures(PxBVHStructure** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
//@}
/** @name Scenes
*/
//@{
/**
\brief Creates a scene.
\note Every scene uses a Thread Local Storage slot. This imposes a platform specific limit on the
number of scenes that can be created.
\param [in] sceneDesc Scene descriptor. See #PxSceneDesc
\return The new scene object.
@see PxScene PxScene.release() PxSceneDesc
*/
virtual PxScene* createScene(const PxSceneDesc& sceneDesc) = 0;
/**
\brief Gets number of created scenes.
\return The number of scenes created.
@see getScene()
*/
virtual PxU32 getNbScenes() const = 0;
/**
\brief Writes the array of scene pointers to a user buffer.
Returns the number of pointers written.
The ordering of the scene pointers in the array is not specified.
\param [out] userBuffer The buffer to receive scene pointers.
\param [in] bufferSize The number of scene pointers which can be stored in the buffer.
\param [in] startIndex Index of first scene pointer to be retrieved
\return The number of scene pointers written to userBuffer, this should be less or equal to bufferSize.
@see getNbScenes() PxScene
*/
virtual PxU32 getScenes(PxScene** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
//@}
/** @name Actors
*/
//@{
/**
\brief Creates a static rigid actor with the specified pose and all other fields initialized
to their default values.
\param [in] pose The initial pose of the actor. Must be a valid transform
@see PxRigidStatic
*/
virtual PxRigidStatic* createRigidStatic(const PxTransform& pose) = 0;
/**
\brief Creates a dynamic rigid actor with the specified pose and all other fields initialized
to their default values.
\param [in] pose The initial pose of the actor. Must be a valid transform
@see PxRigidDynamic
*/
virtual PxRigidDynamic* createRigidDynamic(const PxTransform& pose) = 0;
/**
\brief Creates a pruning structure from actors.
\note Every provided actor needs at least one shape with the eSCENE_QUERY_SHAPE flag set.
\note Both static and dynamic actors can be provided.
\note It is not allowed to pass in actors which are already part of a scene.
\note Articulation links cannot be provided.
\param [in] actors Array of actors to add to the pruning structure. Must be non NULL.
\param [in] nbActors Number of actors in the array. Must be >0.
\return Pruning structure created from given actors, or NULL if any of the actors did not comply with the above requirements.
@see PxActor PxPruningStructure
*/
virtual PxPruningStructure* createPruningStructure(PxRigidActor*const* actors, PxU32 nbActors) = 0;
//@}
/** @name Shapes
*/
//@{
/**
\brief Creates a shape which may be attached to multiple actors
The shape will be created with a reference count of 1.
\param [in] geometry The geometry for the shape
\param [in] material The material for the shape
\param [in] isExclusive Whether this shape is exclusive to a single actor or maybe be shared
\param [in] shapeFlags The PxShapeFlags to be set
Shared shapes are not mutable when they are attached to an actor
@see PxShape
*/
PX_FORCE_INLINE PxShape* createShape( const PxGeometry& geometry,
const PxMaterial& material,
bool isExclusive = false,
PxShapeFlags shapeFlags = PxShapeFlag::eVISUALIZATION | PxShapeFlag::eSCENE_QUERY_SHAPE | PxShapeFlag::eSIMULATION_SHAPE)
{
PxMaterial* materialPtr = const_cast<PxMaterial*>(&material);
return createShape(geometry, &materialPtr, 1, isExclusive, shapeFlags);
}
/**
\brief Creates a shape which may be attached to multiple actors
The shape will be created with a reference count of 1.
\param [in] geometry The geometry for the shape
\param [in] materials The materials for the shape
\param [in] materialCount The number of materials
\param [in] isExclusive Whether this shape is exclusive to a single actor or may be shared
\param [in] shapeFlags The PxShapeFlags to be set
Shared shapes are not mutable when they are attached to an actor
@see PxShape
*/
virtual PxShape* createShape(const PxGeometry& geometry,
PxMaterial*const * materials,
PxU16 materialCount,
bool isExclusive = false,
PxShapeFlags shapeFlags = PxShapeFlag::eVISUALIZATION | PxShapeFlag::eSCENE_QUERY_SHAPE | PxShapeFlag::eSIMULATION_SHAPE) = 0;
/**
\brief Return the number of shapes that currently exist.
\return Number of shapes.
@see getShapes()
*/
virtual PxU32 getNbShapes() const = 0;
/**
\brief Writes the array of shape pointers to a user buffer.
Returns the number of pointers written.
The ordering of the shapes in the array is not specified.
\param [out] userBuffer The buffer to receive shape pointers.
\param [in] bufferSize The number of shape pointers which can be stored in the buffer.
\param [in] startIndex Index of first shape pointer to be retrieved
\return The number of shape pointers written to userBuffer, this should be less or equal to bufferSize.
@see getNbShapes() PxShape
*/
virtual PxU32 getShapes(PxShape** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
//@}
/** @name Constraints and Articulations
*/
//@{
/**
\brief Creates a constraint shader.
\note A constraint shader will get added automatically to the scene the two linked actors belong to. Either, but not both, of actor0 and actor1 may
be NULL to denote attachment to the world.
\param [in] actor0 The first actor
\param [in] actor1 The second actor
\param [in] connector The connector object, which the SDK uses to communicate with the infrastructure for the constraint
\param [in] shaders The shader functions for the constraint
\param [in] dataSize The size of the data block for the shader
\return The new shader.
@see PxConstraint
*/
virtual PxConstraint* createConstraint(PxRigidActor* actor0, PxRigidActor* actor1, PxConstraintConnector& connector, const PxConstraintShaderTable& shaders, PxU32 dataSize) = 0;
/**
\brief Creates an articulation with all fields initialized to their default values.
\return the new articulation
@see PxArticulation, PxRegisterArticulations
*/
virtual PxArticulation* createArticulation() = 0;
/**
\brief Creates a reduced coordinate articulation with all fields initialized to their default values.
\return the new articulation
@see PxArticulationReducedCoordinate, PxRegisterArticulationsReducedCoordinate
*/
virtual PxArticulationReducedCoordinate* createArticulationReducedCoordinate() = 0;
//@}
/** @name Materials
*/
//@{
/**
\brief Creates a new material with default properties.
\return The new material.
\param [in] staticFriction The coefficient of static friction
\param [in] dynamicFriction The coefficient of dynamic friction
\param [in] restitution The coefficient of restitution
@see PxMaterial
*/
virtual PxMaterial* createMaterial(PxReal staticFriction, PxReal dynamicFriction, PxReal restitution) = 0;
/**
\brief Return the number of materials that currently exist.
\return Number of materials.
@see getMaterials()
*/
virtual PxU32 getNbMaterials() const = 0;
/**
\brief Writes the array of material pointers to a user buffer.
Returns the number of pointers written.
The ordering of the materials in the array is not specified.
\param [out] userBuffer The buffer to receive material pointers.
\param [in] bufferSize The number of material pointers which can be stored in the buffer.
\param [in] startIndex Index of first material pointer to be retrieved
\return The number of material pointers written to userBuffer, this should be less or equal to bufferSize.
@see getNbMaterials() PxMaterial
*/
virtual PxU32 getMaterials(PxMaterial** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
//@}
/** @name Deletion Listeners
*/
//@{
/**
\brief Register a deletion listener. Listeners will be called whenever an object is deleted.
It is illegal to register or unregister a deletion listener while deletions are being processed.
\note By default a registered listener will receive events from all objects. Set the restrictedObjectSet parameter to true on registration and use #registerDeletionListenerObjects to restrict the received events to specific objects.
\note The deletion events are only supported on core PhysX objects. In general, objects in extension modules do not provide this functionality, however, in the case of PxJoint objects, the underlying PxConstraint will send the events.
\param [in] observer Observer object to send notifications to.
\param [in] deletionEvents The deletion event types to get notified of.
\param [in] restrictedObjectSet If false, the deletion listener will get events from all objects, else the objects to receive events from have to be specified explicitly through #registerDeletionListenerObjects.
@see PxDeletionListener unregisterDeletionListener
*/
virtual void registerDeletionListener(PxDeletionListener& observer, const PxDeletionEventFlags& deletionEvents, bool restrictedObjectSet = false) = 0;
/**
\brief Unregister a deletion listener.
It is illegal to register or unregister a deletion listener while deletions are being processed.
\param [in] observer Observer object to send notifications to
@see PxDeletionListener registerDeletionListener
*/
virtual void unregisterDeletionListener(PxDeletionListener& observer) = 0;
/**
\brief Register specific objects for deletion events.
This method allows for a deletion listener to limit deletion events to specific objects only.
\note It is illegal to register or unregister objects while deletions are being processed.
\note The deletion listener has to be registered through #registerDeletionListener() and configured to support restricted objects sets prior to this method being used.
\param [in] observer Observer object to send notifications to.
\param [in] observables List of objects for which to receive deletion events. Only PhysX core objects are supported. In the case of PxJoint objects, the underlying PxConstraint can be used to get the events.
\param [in] observableCount Size of the observables list.
@see PxDeletionListener unregisterDeletionListenerObjects
*/
virtual void registerDeletionListenerObjects(PxDeletionListener& observer, const PxBase* const* observables, PxU32 observableCount) = 0;
/**
\brief Unregister specific objects for deletion events.
This method allows to clear previously registered objects for a deletion listener (see #registerDeletionListenerObjects()).
\note It is illegal to register or unregister objects while deletions are being processed.
\note The deletion listener has to be registered through #registerDeletionListener() and configured to support restricted objects sets prior to this method being used.
\param [in] observer Observer object to stop sending notifications to.
\param [in] observables List of objects for which to not receive deletion events anymore.
\param [in] observableCount Size of the observables list.
@see PxDeletionListener registerDeletionListenerObjects
*/
virtual void unregisterDeletionListenerObjects(PxDeletionListener& observer, const PxBase* const* observables, PxU32 observableCount) = 0;
/**
\brief Gets PxPhysics object insertion interface.
The insertion interface is needed ie. for PxCooking::createTriangleMesh, this allows runtime mesh creation. This is not advised to do, please
use offline cooking if possible.
@see PxCooking::createTriangleMesh PxCooking::createHeightfield
*/
virtual PxPhysicsInsertionCallback& getPhysicsInsertionCallback() = 0;
//@}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/**
\brief Enables the usage of the articulations feature. This function is called automatically inside PxCreatePhysics().
On resource constrained platforms, it is possible to call PxCreateBasePhysics() and then NOT call this function
to save on code memory if your application does not use articulations. In this case the linker should strip out
the relevant implementation code from the library. If you need to use articulations but not some other optional
component, you shoud call PxCreateBasePhysics() followed by this call.
*/
PX_C_EXPORT PX_PHYSX_CORE_API void PX_CALL_CONV PxRegisterArticulations(physx::PxPhysics& physics);
/**
\brief Enables the usage of the reduced coordinate articulations feature. This function is called automatically inside PxCreatePhysics().
On resource constrained platforms, it is possible to call PxCreateBasePhysics() and then NOT call this function
to save on code memory if your application does not use articulations. In this case the linker should strip out
the relevant implementation code from the library. If you need to use articulations but not some other optional
component, you shoud call PxCreateBasePhysics() followed by this call.
*/
PX_C_EXPORT PX_PHYSX_CORE_API void PX_CALL_CONV PxRegisterArticulationsReducedCoordinate(physx::PxPhysics& physics);
/**
\brief Enables the usage of the heightfield feature.
This call will link the default 'unified' implementation of heightfields which is identical to the narrow phase of triangle meshes.
This function is called automatically inside PxCreatePhysics().
On resource constrained platforms, it is possible to call PxCreateBasePhysics() and then NOT call this function
to save on code memory if your application does not use heightfields. In this case the linker should strip out
the relevant implementation code from the library. If you need to use heightfield but not some other optional
component, you shoud call PxCreateBasePhysics() followed by this call.
You must call this function at a time where no ::PxScene instance exists, typically before calling PxPhysics::createScene().
This is to prevent a change to the heightfield implementation code at runtime which would have undefined results.
Calling PxCreateBasePhysics() and then attempting to create a heightfield shape without first calling
::PxRegisterHeightFields(), will result in an error.
*/
PX_C_EXPORT PX_PHYSX_CORE_API void PX_CALL_CONV PxRegisterHeightFields(physx::PxPhysics& physics);
/**
\brief Creates an instance of the physics SDK with minimal additional components registered
Creates an instance of this class. May not be a class member to avoid name mangling.
Pass the constant #PX_PHYSICS_VERSION as the argument.
There may be only one instance of this class per process. Calling this method after an instance
has been created already will result in an error message and NULL will be returned.
\param version Version number we are expecting(should be #PX_PHYSICS_VERSION)
\param foundation Foundation instance (see PxFoundation)
\param scale values used to determine default tolerances for objects at creation time
\param trackOutstandingAllocations true if you want to track memory allocations
so a debugger connection partway through your physics simulation will get
an accurate map of everything that has been allocated so far. This could have a memory
and performance impact on your simulation hence it defaults to off.
\param pvd When pvd points to a valid PxPvd instance (PhysX Visual Debugger), a connection to the specified PxPvd instance is created.
If pvd is NULL no connection will be attempted.
\return PxPhysics instance on success, NULL if operation failed
@see PxPhysics, PxFoundation, PxTolerancesScale, PxPvd
*/
PX_C_EXPORT PX_PHYSX_CORE_API physx::PxPhysics* PX_CALL_CONV PxCreateBasePhysics(physx::PxU32 version,
physx::PxFoundation& foundation,
const physx::PxTolerancesScale& scale,
bool trackOutstandingAllocations = false,
physx::PxPvd* pvd = NULL);
/**
\brief Creates an instance of the physics SDK.
Creates an instance of this class. May not be a class member to avoid name mangling.
Pass the constant #PX_PHYSICS_VERSION as the argument.
There may be only one instance of this class per process. Calling this method after an instance
has been created already will result in an error message and NULL will be returned.
Calling this will register all optional code modules (Articulations and HeightFields), preparing them for use.
If you do not need some of these modules, consider calling PxCreateBasePhysics() instead and registering needed
modules manually.
\param version Version number we are expecting(should be #PX_PHYSICS_VERSION)
\param foundation Foundation instance (see PxFoundation)
\param scale values used to determine default tolerances for objects at creation time
\param trackOutstandingAllocations true if you want to track memory allocations
so a debugger connection partway through your physics simulation will get
an accurate map of everything that has been allocated so far. This could have a memory
and performance impact on your simulation hence it defaults to off.
\param pvd When pvd points to a valid PxPvd instance (PhysX Visual Debugger), a connection to the specified PxPvd instance is created.
If pvd is NULL no connection will be attempted.
\return PxPhysics instance on success, NULL if operation failed
@see PxPhysics, PxCreateBasePhysics, PxRegisterArticulations, PxRegisterArticulationsReducedCoordinate, PxRegisterHeightFields
*/
PX_INLINE physx::PxPhysics* PxCreatePhysics(physx::PxU32 version,
physx::PxFoundation& foundation,
const physx::PxTolerancesScale& scale,
bool trackOutstandingAllocations = false,
physx::PxPvd* pvd = NULL )
{
physx::PxPhysics* physics = PxCreateBasePhysics(version, foundation, scale, trackOutstandingAllocations, pvd);
if(!physics)
return NULL;
PxRegisterArticulations(*physics);
PxRegisterArticulationsReducedCoordinate(*physics);
PxRegisterHeightFields(*physics);
return physics;
}
/**
\brief Retrieves the Physics SDK after it has been created.
Before using this function the user must call #PxCreatePhysics().
\note The behavior of this method is undefined if the Physics SDK instance has not been created already.
*/
#ifdef __clang__
#pragma clang diagnostic push
#pragma clang diagnostic ignored "-Wreturn-type-c-linkage"
#endif
PX_C_EXPORT PX_PHYSX_CORE_API physx::PxPhysics& PX_CALL_CONV PxGetPhysics();
#ifdef __clang__
#pragma clang diagnostic pop
#endif
/** @} */
#endif

View File

@ -0,0 +1,218 @@
//
// 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-2018 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_NXPHYSICS_API
#define PX_PHYSICS_NXPHYSICS_API
/** \addtogroup physics
@{
*/
/**
This is the main include header for the Physics SDK, for users who
want to use a single #include file.
Alternatively, one can instead directly #include a subset of the below files.
*/
// Foundation SDK
#include "foundation/Px.h"
#include "foundation/PxAllocatorCallback.h"
#include "foundation/PxAssert.h"
#include "foundation/PxBitAndData.h"
#include "foundation/PxBounds3.h"
#include "foundation/PxErrorCallback.h"
#include "foundation/PxErrors.h"
#include "foundation/PxFlags.h"
#include "foundation/PxIntrinsics.h"
#include "foundation/PxIO.h"
#include "foundation/PxMat33.h"
#include "foundation/PxMat44.h"
#include "foundation/PxMath.h"
#include "foundation/PxMathUtils.h"
#include "foundation/PxPlane.h"
#include "foundation/PxPreprocessor.h"
#include "foundation/PxQuat.h"
#include "foundation/PxSimpleTypes.h"
#include "foundation/PxStrideIterator.h"
#include "foundation/PxTransform.h"
#include "foundation/PxUnionCast.h"
#include "foundation/PxVec2.h"
#include "foundation/PxVec3.h"
#include "foundation/PxVec4.h"
//Not physics specific utilities and common code
#include "common/PxCoreUtilityTypes.h"
#include "common/PxPhysXCommonConfig.h"
#include "common/PxRenderBuffer.h"
#include "common/PxBase.h"
#include "common/PxTolerancesScale.h"
#include "common/PxTypeInfo.h"
#include "common/PxStringTable.h"
#include "common/PxSerializer.h"
#include "common/PxMetaData.h"
#include "common/PxMetaDataFlags.h"
#include "common/PxSerialFramework.h"
#include "common/PxPhysicsInsertionCallback.h"
//Task Manager
#include "task/PxTask.h"
// Cuda Mananger
#if PX_SUPPORT_GPU_PHYSX
#include "gpu/PxGpu.h"
#endif
//Geometry Library
#include "geometry/PxBoxGeometry.h"
#include "geometry/PxBVHStructure.h"
#include "geometry/PxCapsuleGeometry.h"
#include "geometry/PxConvexMesh.h"
#include "geometry/PxConvexMeshGeometry.h"
#include "geometry/PxGeometry.h"
#include "geometry/PxGeometryHelpers.h"
#include "geometry/PxGeometryQuery.h"
#include "geometry/PxHeightField.h"
#include "geometry/PxHeightFieldDesc.h"
#include "geometry/PxHeightFieldFlag.h"
#include "geometry/PxHeightFieldGeometry.h"
#include "geometry/PxHeightFieldSample.h"
#include "geometry/PxMeshQuery.h"
#include "geometry/PxMeshScale.h"
#include "geometry/PxPlaneGeometry.h"
#include "geometry/PxSimpleTriangleMesh.h"
#include "geometry/PxSphereGeometry.h"
#include "geometry/PxTriangle.h"
#include "geometry/PxTriangleMesh.h"
#include "geometry/PxTriangleMeshGeometry.h"
// PhysX Core SDK
#include "PxActor.h"
#include "PxAggregate.h"
#include "PxArticulation.h"
#include "PxArticulationReducedCoordinate.h"
#include "PxArticulationJoint.h"
#include "PxArticulationJointReducedCoordinate.h"
#include "PxArticulationLink.h"
#include "PxBatchQuery.h"
#include "PxBatchQueryDesc.h"
#include "PxClient.h"
#include "PxConstraint.h"
#include "PxConstraintDesc.h"
#include "PxContact.h"
#include "PxContactModifyCallback.h"
#include "PxDeletionListener.h"
#include "PxFiltering.h"
#include "PxForceMode.h"
#include "PxFoundation.h"
#include "PxLockedData.h"
#include "PxMaterial.h"
#include "PxPhysics.h"
#include "PxPhysicsVersion.h"
#include "PxPhysXConfig.h"
#include "PxQueryFiltering.h"
#include "PxQueryReport.h"
#include "PxRigidActor.h"
#include "PxRigidBody.h"
#include "PxRigidDynamic.h"
#include "PxRigidStatic.h"
#include "PxScene.h"
#include "PxSceneDesc.h"
#include "PxSceneLock.h"
#include "PxShape.h"
#include "PxSimulationEventCallback.h"
#include "PxSimulationStatistics.h"
#include "PxVisualizationParameter.h"
#include "PxPruningStructure.h"
//Character Controller
#include "characterkinematic/PxBoxController.h"
#include "characterkinematic/PxCapsuleController.h"
#include "characterkinematic/PxCharacter.h"
#include "characterkinematic/PxController.h"
#include "characterkinematic/PxControllerBehavior.h"
#include "characterkinematic/PxControllerManager.h"
#include "characterkinematic/PxControllerObstacles.h"
#include "characterkinematic/PxExtended.h"
//Cooking (data preprocessing)
#include "cooking/Pxc.h"
#include "cooking/PxConvexMeshDesc.h"
#include "cooking/PxCooking.h"
#include "cooking/PxTriangleMeshDesc.h"
#include "cooking/PxBVH33MidphaseDesc.h"
#include "cooking/PxBVH34MidphaseDesc.h"
#include "cooking/PxMidphaseDesc.h"
//Extensions to the SDK
#include "extensions/PxDefaultStreams.h"
#include "extensions/PxDistanceJoint.h"
#include "extensions/PxExtensionsAPI.h"
#include "extensions/PxFixedJoint.h"
#include "extensions/PxJoint.h"
#include "extensions/PxJointLimit.h"
#include "extensions/PxPrismaticJoint.h"
#include "extensions/PxRevoluteJoint.h"
#include "extensions/PxRigidBodyExt.h"
#include "extensions/PxShapeExt.h"
#include "extensions/PxSimpleFactory.h"
#include "extensions/PxSmoothNormals.h"
#include "extensions/PxSphericalJoint.h"
#include "extensions/PxStringTableExt.h"
#include "extensions/PxTriangleMeshExt.h"
#include "extensions/PxConvexMeshExt.h"
//Serialization
#include "extensions/PxSerialization.h"
#include "extensions/PxBinaryConverter.h"
#include "extensions/PxRepXSerializer.h"
//Vehicle Simulation
#include "vehicle/PxVehicleComponents.h"
#include "vehicle/PxVehicleDrive.h"
#include "vehicle/PxVehicleDrive4W.h"
#include "vehicle/PxVehicleDriveTank.h"
#include "vehicle/PxVehicleSDK.h"
#include "vehicle/PxVehicleShaders.h"
#include "vehicle/PxVehicleTireFriction.h"
#include "vehicle/PxVehicleUpdate.h"
#include "vehicle/PxVehicleUtilControl.h"
#include "vehicle/PxVehicleUtilSetup.h"
#include "vehicle/PxVehicleUtilTelemetry.h"
#include "vehicle/PxVehicleWheels.h"
#include "vehicle/PxVehicleNoDrive.h"
#include "vehicle/PxVehicleDriveNW.h"
//Connecting the SDK to Visual Debugger
#include "pvd/PxPvdSceneClient.h"
#include "pvd/PxPvd.h"
#include "pvd/PxPvdTransport.h"
/** @} */
#endif

View File

@ -0,0 +1,74 @@
//
// 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-2018 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_PX_PHYSICS_SERIALIZATION
#define PX_PHYSICS_PX_PHYSICS_SERIALIZATION
#include "PxPhysXConfig.h"
#include "common/PxSerialFramework.h"
#if !PX_DOXYGEN
/**
\brief Retrieves the PhysX SDK metadata.
This function is used to implement PxSerialization.dumpBinaryMetaData() and is not intended to be needed otherwise.
@see PxSerialization.dumpBinaryMetaData()
*/
PX_C_EXPORT PX_PHYSX_CORE_API void PX_CALL_CONV PxGetPhysicsBinaryMetaData(physx::PxOutputStream& stream);
/**
\brief Registers physics classes for serialization.
This function is used to implement PxSerialization.createSerializationRegistry() and is not intended to be needed otherwise.
@see PxSerializationRegistry
*/
PX_C_EXPORT PX_PHYSX_CORE_API void PX_CALL_CONV PxRegisterPhysicsSerializers(physx::PxSerializationRegistry& sr);
/**
\brief Unregisters physics classes for serialization.
This function is used in the release implementation of PxSerializationRegistry and in not intended to be used otherwise.
@see PxSerializationRegistry
*/
PX_C_EXPORT PX_PHYSX_CORE_API void PX_CALL_CONV PxUnregisterPhysicsSerializers(physx::PxSerializationRegistry& sr);
/**
\brief Adds collected objects to PxPhysics.
This function adds all objects contained in the input collection to the PxPhysics instance. This is used after deserializing
the collection, to populate the physics with inplace deserialized objects. This function is used in the implementation of
PxSerialization.createCollectionFromBinary and is not intended to be needed otherwise.
\param[in] collection Objects to add to the PxPhysics instance.
@see PxCollection, PxSerialization.createCollectionFromBinary
*/
PX_C_EXPORT PX_PHYSX_CORE_API void PX_CALL_CONV PxAddCollectionToPhysics(const physx::PxCollection& collection);
#endif // !PX_DOXYGEN
#endif // PX_PHYSICS_PX_PHYSICS_SERIALIZATION

View File

@ -0,0 +1,70 @@
//
// 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-2018 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_VERSION_NUMBER_H
#define PX_PHYSICS_VERSION_NUMBER_H
/*
VersionNumbers: The combination of these
numbers uniquely identifies the API, and should
be incremented when the SDK API changes. This may
include changes to file formats.
This header is included in the main SDK header files
so that the entire SDK and everything that builds on it
is completely rebuilt when this file changes. Thus,
this file is not to include a frequently changing
build number. See BuildNumber.h for that.
Each of these three values should stay below 255 because
sometimes they are stored in a byte.
*/
/** \addtogroup foundation
@{
*/
//
// Important: if you adjust the versions below, don't forget to adjust the compatibility list in
// sBinaryCompatibleVersions as well.
//
#define PX_PHYSICS_VERSION_MAJOR 4
#define PX_PHYSICS_VERSION_MINOR 0
#define PX_PHYSICS_VERSION_BUGFIX 0
/**
The constant PX_PHYSICS_VERSION is used when creating certain PhysX module objects.
This is to ensure that the application is using the same header version as the library was built with.
*/
#define PX_PHYSICS_VERSION ((PX_PHYSICS_VERSION_MAJOR<<24) + (PX_PHYSICS_VERSION_MINOR<<16) + (PX_PHYSICS_VERSION_BUGFIX<<8) + 0)
#endif // PX_PHYSICS_VERSION_NUMBER_H
/** @} */

View File

@ -0,0 +1,109 @@
//
// 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-2018 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_PRUNING_STRUCTURE
#define PX_PHYSICS_NX_PRUNING_STRUCTURE
/** \addtogroup physics
@{ */
#include "PxPhysXConfig.h"
#include "common/PxBase.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief A precomputed pruning structure to accelerate scene queries against newly added actors.
The pruning structure can be provided to #PxScene:: addActors() in which case it will get merged
directly into the scene query optimization AABB tree, thus leading to improved performance when
doing queries against the newly added actors. This applies to both static and dynamic actors.
\note PxPruningStructure objects can be added to a collection and get serialized.
\note Adding a PxPruningStructure object to a collection will also add the actors that were used to build the pruning structure.
\note PxPruningStructure must be released before its rigid actors.
\note PxRigidBody objects can be in one PxPruningStructure only.
\note Changing the bounds of PxRigidBody objects assigned to a pruning structure that has not been added to a scene yet will
invalidate the pruning structure. Same happens if shape scene query flags change or shape gets removed from an actor.
@see PxScene::addActors PxCollection
*/
class PxPruningStructure : public PxBase
{
public:
/**
\brief Release this object.
*/
virtual void release() = 0;
/**
\brief Retrieve rigid actors in the pruning structure.
You can retrieve the number of rigid actor pointers by calling #getNbRigidActors()
\param[out] userBuffer The buffer to store the actor pointers.
\param[in] bufferSize Size of provided user buffer.
\param[in] startIndex Index of first actor pointer to be retrieved
\return Number of rigid actor pointers written to the buffer.
@see PxRigidActor
*/
virtual PxU32 getRigidActors(PxRigidActor** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
/**
\brief Returns the number of rigid actors in the pruning structure.
You can use #getRigidActors() to retrieve the rigid actor pointers.
\return Number of rigid actors in the pruning structure.
@see PxRigidActor
*/
virtual PxU32 getNbRigidActors() const = 0;
virtual const char* getConcreteTypeName() const { return "PxPruningStructure"; }
protected:
PX_INLINE PxPruningStructure(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags) {}
PX_INLINE PxPruningStructure(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
virtual ~PxPruningStructure() {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxPruningStructure", name) || PxBase::isKindOf(name); }
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif // PX_PHYSICS_NX_PRUNING_STRUCTURE

View File

@ -0,0 +1,276 @@
//
// 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-2018 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_SCENE_QUERY_FILTERING
#define PX_PHYSICS_NX_SCENE_QUERY_FILTERING
/** \addtogroup scenequery
@{
*/
#include "PxPhysXConfig.h"
#include "PxFiltering.h"
#include "PxQueryReport.h"
#include "PxClient.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxShape;
class PxRigidActor;
struct PxQueryHit;
/**
\brief Filtering flags for scene queries.
@see PxQueryFilterData.flags
*/
struct PxQueryFlag
{
enum Enum
{
eSTATIC = (1<<0), //!< Traverse static shapes
eDYNAMIC = (1<<1), //!< Traverse dynamic shapes
ePREFILTER = (1<<2), //!< Run the pre-intersection-test filter (see #PxQueryFilterCallback::preFilter())
ePOSTFILTER = (1<<3), //!< Run the post-intersection-test filter (see #PxQueryFilterCallback::postFilter())
eANY_HIT = (1<<4), //!< Abort traversal as soon as any hit is found and return it via callback.block.
//!< Helps query performance. Both eTOUCH and eBLOCK hitTypes are considered hits with this flag.
eNO_BLOCK = (1<<5), //!< All hits are reported as touching. Overrides eBLOCK returned from user filters with eTOUCH.
//!< This is also an optimization hint that may improve query performance.
eRESERVED = (1<<15) //!< Reserved for internal use
};
};
PX_COMPILE_TIME_ASSERT(PxQueryFlag::eSTATIC==(1<<0));
PX_COMPILE_TIME_ASSERT(PxQueryFlag::eDYNAMIC==(1<<1));
/**
\brief Flags typedef for the set of bits defined in PxQueryFlag.
*/
typedef PxFlags<PxQueryFlag::Enum,PxU16> PxQueryFlags;
PX_FLAGS_OPERATORS(PxQueryFlag::Enum,PxU16)
/**
\brief Classification of scene query hits (intersections).
- eNONE: Returning this hit type means that the hit should not be reported.
- eBLOCK: For all raycast, sweep and overlap queries the nearest eBLOCK type hit will always be returned in PxHitCallback::block member.
- eTOUCH: Whenever a raycast, sweep or overlap query was called with non-zero PxHitCallback::nbTouches and PxHitCallback::touches
parameters, eTOUCH type hits that are closer or same distance (touchDistance <= blockDistance condition)
as the globally nearest eBLOCK type hit, will be reported.
- For example, to record all hits from a raycast query, always return eTOUCH.
All hits in overlap() queries are treated as if the intersection distance were zero.
This means the hits are unsorted and all eTOUCH hits are recorded by the callback even if an eBLOCK overlap hit was encountered.
Even though all overlap() blocking hits have zero length, only one (arbitrary) eBLOCK overlap hit is recorded in PxHitCallback::block.
All overlap() eTOUCH type hits are reported (zero touchDistance <= zero blockDistance condition).
For raycast/sweep/overlap calls with zero touch buffer or PxHitCallback::nbTouches member,
only the closest hit of type eBLOCK is returned. All eTOUCH hits are discarded.
@see PxQueryFilterCallback.preFilter PxQueryFilterCallback.postFilter PxScene.raycast PxScene.sweep PxScene.overlap
*/
struct PxQueryHitType
{
enum Enum
{
eNONE = 0, //!< the query should ignore this shape
eTOUCH = 1, //!< a hit on the shape touches the intersection geometry of the query but does not block it
eBLOCK = 2 //!< a hit on the shape blocks the query (does not block overlap queries)
};
};
/**
\brief Scene query filtering data.
Whenever the scene query intersects a shape, filtering is performed in the following order:
\li For non-batched queries only:<br>If the data field is non-zero, and the bitwise-AND value of data AND the shape's
queryFilterData is zero, the shape is skipped
\li If filter callbacks are enabled in flags field (see #PxQueryFlags) they will get invoked accordingly.
\li If neither #PxQueryFlag::ePREFILTER or #PxQueryFlag::ePOSTFILTER is set, the hit defaults
to type #PxQueryHitType::eBLOCK when the value of PxHitCallback::nbTouches provided with the query is zero and to type
#PxQueryHitType::eTOUCH when PxHitCallback::nbTouches is positive.
@see PxScene.raycast PxScene.sweep PxScene.overlap PxBatchQuery.raycast PxBatchQuery.sweep PxBatchQuery.overlap PxQueryFlag::eANY_HIT
*/
struct PxQueryFilterData
{
/** \brief default constructor */
explicit PX_INLINE PxQueryFilterData() : flags(PxQueryFlag::eDYNAMIC | PxQueryFlag::eSTATIC) {}
/** \brief constructor to set both filter data and filter flags */
explicit PX_INLINE PxQueryFilterData(const PxFilterData& fd, PxQueryFlags f) : data(fd), flags(f) {}
/** \brief constructor to set filter flags only */
explicit PX_INLINE PxQueryFilterData(PxQueryFlags f) : flags(f) {}
PxFilterData data; //!< Filter data associated with the scene query
PxQueryFlags flags; //!< Filter flags (see #PxQueryFlags)
};
/**
\brief Scene query filtering callbacks.
Custom filtering logic for scene query intersection candidates. If an intersection candidate object passes the data based filter
(see #PxQueryFilterData), filtering callbacks are executed if requested (see #PxQueryFilterData.flags)
\li If #PxQueryFlag::ePREFILTER is set, the preFilter function runs before exact intersection tests.
If this function returns #PxQueryHitType::eTOUCH or #PxQueryHitType::eBLOCK, exact testing is performed to
determine the intersection location.
The preFilter function may overwrite the copy of queryFlags it receives as an argument to specify any of #PxHitFlag::eMODIFIABLE_FLAGS
on a per-shape basis. Changes apply only to the shape being filtered, and changes to other flags are ignored.
\li If #PxQueryFlag::ePREFILTER is not set, precise intersection testing is performed using the original query's filterData.flags.
\li If #PxQueryFlag::ePOSTFILTER is set, the postFilter function is called for each intersection to determine the touch/block status.
This overrides any touch/block status previously returned from the preFilter function for this shape.
Filtering calls are not guaranteed to be sorted along the ray or sweep direction.
@see PxScene.raycast PxScene.sweep PxScene.overlap PxQueryFlags PxHitFlags
*/
class PxQueryFilterCallback
{
public:
/**
\brief This filter callback is executed before the exact intersection test if PxQueryFlag::ePREFILTER flag was set.
\param[in] filterData custom filter data specified as the query's filterData.data parameter.
\param[in] shape A shape that has not yet passed the exact intersection test.
\param[in] actor The shape's actor.
\param[in,out] queryFlags scene query flags from the query's function call (only flags from PxHitFlag::eMODIFIABLE_FLAGS bitmask can be modified)
\return the updated type for this hit (see #PxQueryHitType)
*/
virtual PxQueryHitType::Enum preFilter(
const PxFilterData& filterData, const PxShape* shape, const PxRigidActor* actor, PxHitFlags& queryFlags) = 0;
/**
\brief This filter callback is executed if the exact intersection test returned true and PxQueryFlag::ePOSTFILTER flag was set.
\param[in] filterData custom filter data of the query
\param[in] hit Scene query hit information. faceIndex member is not valid for overlap queries. For sweep and raycast queries the hit information can be cast to #PxSweepHit and #PxRaycastHit respectively.
\return the updated hit type for this hit (see #PxQueryHitType)
*/
virtual PxQueryHitType::Enum postFilter(const PxFilterData& filterData, const PxQueryHit& hit) = 0;
/**
\brief virtual destructor
*/
virtual ~PxQueryFilterCallback() {}
};
/**
\brief Batched query pre-filter shader.
Custom filtering logic for batched query intersection candidates. If an intersection candidate object passes the data based filter (see #PxQueryFilterData),
filtering shader runs if specified in filtering flags (see #PxQueryFilterData.flags)
\li If #PxQueryFlag::ePREFILTER is set, the preFilter shader runs before exact intersection tests.
If the shader returns #PxQueryHitType::eTOUCH or #PxQueryHitType::eBLOCK, exact testing is performed to
determine the intersection location.
The preFilter shader may overwrite the copy of queryFlags it receives as an argument to specify any of #PxHitFlag::eMODIFIABLE_FLAGS
on a per-shape basis. Changes apply only to the shape being filtered, and changes to other flags are ignored.
\li If #PxQueryFlag::ePREFILTER is not set, precise intersection testing is performed using the original query's filterData.flags.
Filtering calls are not guaranteed to be sorted along the ray or sweep direction.
\deprecated The batched query feature has been deprecated in PhysX version 3.4
@see PxBatchQueryDesc.preFilterShader PxQueryFilterCallback.preFilter PxBatchQueryPostFilterShader
*/
/**
\param[in] queryFilterData Query filter data
\param[in] objectFilterData Object filter data
\param[in] constantBlock Global constant filter data (see #PxBatchQuery)
\param[in] constantBlockSize Size of global filter data (see #PxBatchQuery)
\param[in,out] hitFlags Per-object modifiable hit flags (only flags from PxHitFlag::eMODIFIABLE_FLAGS mask can be modified)
\return the updated hit type for this hit (see #PxQueryHitType)
@see PxBatchQueryPostFilterShader
*/
typedef PX_DEPRECATED PxQueryHitType::Enum (*PxBatchQueryPreFilterShader)(
PxFilterData queryFilterData, PxFilterData objectFilterData,
const void* constantBlock, PxU32 constantBlockSize,
PxHitFlags& hitFlags);
/**
\brief Batched query post-filter shader.
Custom filtering logic for batched query intersection candidates. If an intersection candidate object passes the data based filter (see #PxQueryFilterData),
the filtering shader run on request (see #PxQueryFilterData.flags)
\li If #PxQueryFlag::ePOSTFILTER is set, the postFilter shader is called for each intersection to determine the touch/block status.
This overrides any touch/block status previously returned from the preFilter function for this shape.
Filtering shaders are not in order along the query direction, rather they are processed in the order in which
candidate shapes for testing are found by PhysX' scene traversal algorithms.
\deprecated The batched query feature has been deprecated in PhysX version 3.4
@see PxBatchQueryDesc.postFilterShader PxQueryFilterCallback.postFilter PxBatchQueryPreFilterShader
*/
/**
\param[in] queryFilterData Query filter data
\param[in] objectFilterData Object filter data
\param[in] constantBlock Global constant filter data (see #PxBatchQuery)
\param[in] constantBlockSize Size of global filter data (see #PxBatchQuery)
\param[in] hit Hit data from the prior exact intersection test.
\return the new hit type for this hit (see #PxQueryHitType)
@see PxBatchQueryPreFilterShader
*/
typedef PX_DEPRECATED PxQueryHitType::Enum (*PxBatchQueryPostFilterShader)(
PxFilterData queryFilterData, PxFilterData objectFilterData,
const void* constantBlock, PxU32 constantBlockSize,
const PxQueryHit& hit);
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,390 @@
//
// 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-2018 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_SCENEQUERYREPORT
#define PX_PHYSICS_NX_SCENEQUERYREPORT
/** \addtogroup scenequery
@{
*/
#include "PxPhysXConfig.h"
#include "foundation/PxVec3.h"
#include "foundation/PxFlags.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxShape;
class PxRigidActor;
/**
\brief Scene query and geometry query behavior flags.
PxHitFlags are used for 3 different purposes:
1) To request hit fields to be filled in by scene queries (such as hit position, normal, face index or UVs).
2) Once query is completed, to indicate which fields are valid (note that a query may produce more valid fields than requested).
3) To specify additional options for the narrow phase and mid-phase intersection routines.
All these flags apply to both scene queries and geometry queries (PxGeometryQuery).
@see PxRaycastHit PxSweepHit PxOverlapHit PxScene.raycast PxScene.sweep PxScene.overlap PxGeometryQuery PxFindFaceIndex
*/
struct PxHitFlag
{
enum Enum
{
ePOSITION = (1<<0), //!< "position" member of #PxQueryHit is valid
eNORMAL = (1<<1), //!< "normal" member of #PxQueryHit is valid
eUV = (1<<3), //!< "u" and "v" barycentric coordinates of #PxQueryHit are valid. Not applicable to sweep queries.
eASSUME_NO_INITIAL_OVERLAP = (1<<4), //!< Performance hint flag for sweeps when it is known upfront there's no initial overlap.
//!< NOTE: using this flag may cause undefined results if shapes are initially overlapping.
eMESH_MULTIPLE = (1<<5), //!< Report all hits for meshes rather than just the first. Not applicable to sweep queries.
eMESH_ANY = (1<<6), //!< Report any first hit for meshes. If neither eMESH_MULTIPLE nor eMESH_ANY is specified,
//!< a single closest hit will be reported for meshes.
eMESH_BOTH_SIDES = (1<<7), //!< Report hits with back faces of mesh triangles. Also report hits for raycast
//!< originating on mesh surface and facing away from the surface normal. Not applicable to sweep queries.
//!< Please refer to the user guide for heightfield-specific differences.
ePRECISE_SWEEP = (1<<8), //!< Use more accurate but slower narrow phase sweep tests.
//!< May provide better compatibility with PhysX 3.2 sweep behavior.
eMTD = (1<<9), //!< Report the minimum translation depth, normal and contact point.
eFACE_INDEX = (1<<10), //!< "face index" member of #PxQueryHit is valid
eDEFAULT = ePOSITION|eNORMAL|eFACE_INDEX,
/** \brief Only this subset of flags can be modified by pre-filter. Other modifications will be discarded. */
eMODIFIABLE_FLAGS = eMESH_MULTIPLE|eMESH_BOTH_SIDES|eASSUME_NO_INITIAL_OVERLAP|ePRECISE_SWEEP
};
};
/**
\brief collection of set bits defined in PxHitFlag.
@see PxHitFlag
*/
PX_FLAGS_TYPEDEF(PxHitFlag, PxU16)
/**
\brief Combines a shape pointer and the actor the shape belongs to into one memory location.
Serves as a base class for PxQueryHit.
@see PxQueryHit
*/
struct PxActorShape
{
PX_INLINE PxActorShape() : actor(NULL), shape(NULL) {}
PX_INLINE PxActorShape(PxRigidActor* a, PxShape* s) : actor(a), shape(s) {}
PxRigidActor* actor;
PxShape* shape;
};
/**
\brief Scene query hit information.
*/
struct PxQueryHit : public PxActorShape
{
PX_INLINE PxQueryHit() : faceIndex(0xFFFFffff) {}
/**
Face index of touched triangle, for triangle meshes, convex meshes and height fields.
\note This index will default to 0xFFFFffff value for overlap queries.
\note Please refer to the user guide for more details for sweep queries.
\note This index is remapped by mesh cooking. Use #PxTriangleMesh::getTrianglesRemap() to convert to original mesh index.
\note For convex meshes use #PxConvexMesh::getPolygonData() to retrieve touched polygon data.
*/
PxU32 faceIndex;
};
/**
\brief Scene query hit information for raycasts and sweeps returning hit position and normal information.
::PxHitFlag flags can be passed to scene query functions, as an optimization, to cause the SDK to
only generate specific members of this structure.
*/
struct PxLocationHit : public PxQueryHit
{
PX_INLINE PxLocationHit() : flags(0), position(PxVec3(0)), normal(PxVec3(0)), distance(PX_MAX_REAL) {}
/**
\note For raycast hits: true for shapes overlapping with raycast origin.
\note For sweep hits: true for shapes overlapping at zero sweep distance.
@see PxRaycastHit PxSweepHit
*/
PX_INLINE bool hadInitialOverlap() const { return (distance <= 0.0f); }
// the following fields are set in accordance with the #PxHitFlags
PxHitFlags flags; //!< Hit flags specifying which members contain valid values.
PxVec3 position; //!< World-space hit position (flag: #PxHitFlag::ePOSITION)
PxVec3 normal; //!< World-space hit normal (flag: #PxHitFlag::eNORMAL)
/**
\brief Distance to hit.
\note If the eMTD flag is used, distance will be a negative value if shapes are overlapping indicating the penetration depth.
\note Otherwise, this value will be >= 0 */
PxF32 distance;
};
/**
\brief Stores results of raycast queries.
::PxHitFlag flags can be passed to raycast function, as an optimization, to cause the SDK to only compute specified members of this
structure.
Some members like barycentric coordinates are currently only computed for triangle meshes and height fields, but next versions
might provide them in other cases. The client code should check #flags to make sure returned values are valid.
@see PxScene.raycast PxBatchQuery.raycast
*/
struct PxRaycastHit : public PxLocationHit
{
PX_INLINE PxRaycastHit() : u(0.0f), v(0.0f) {}
// the following fields are set in accordance with the #PxHitFlags
PxReal u, v; //!< barycentric coordinates of hit point, for triangle mesh and height field (flag: #PxHitFlag::eUV)
#if !PX_P64_FAMILY
PxU32 padTo16Bytes[3];
#endif
};
/**
\brief Stores results of overlap queries.
@see PxScene.overlap PxBatchQuery.overlap
*/
struct PxOverlapHit: public PxQueryHit { PxU32 padTo16Bytes; };
/**
\brief Stores results of sweep queries.
@see PxScene.sweep PxBatchQuery.sweep
*/
struct PxSweepHit : public PxLocationHit
{
PX_INLINE PxSweepHit() {}
PxU32 padTo16Bytes;
};
/**
\brief Describes query behavior after returning a partial query result via a callback.
If callback returns true, traversal will continue and callback can be issued again.
If callback returns false, traversal will stop, callback will not be issued again.
@see PxHitCallback
*/
typedef bool PxAgain;
/**
\brief This callback class facilitates reporting scene query hits (intersections) to the user.
User overrides the virtual processTouches function to receive hits in (possibly multiple) fixed size blocks.
\note PxHitBuffer derives from this class and is used to receive touching hits in a fixed size buffer.
\note Since the compiler doesn't look in template dependent base classes when looking for non-dependent names
\note with some compilers it will be necessary to use "this->hasBlock" notation to access a parent variable
\note in a child callback class.
\note Pre-made typedef shorthands, such as ::PxRaycastCallback can be used for raycast, overlap and sweep queries.
@see PxHitBuffer PxRaycastHit PxSweepHit PxOverlapHit PxRaycastCallback PxOverlapCallback PxSweepCallback
*/
template<typename HitType>
struct PxHitCallback
{
HitType block; //!< Holds the closest blocking hit result for the query. Invalid if hasBlock is false.
bool hasBlock; //!< Set to true if there was a blocking hit during query.
HitType* touches; //!< User specified buffer for touching hits.
/**
\brief Size of the user specified touching hits buffer.
\note If set to 0 all hits will default to PxQueryHitType::eBLOCK, otherwise to PxQueryHitType::eTOUCH
\note Hit type returned from pre-filter overrides this default */
PxU32 maxNbTouches;
/**
\brief Number of touching hits returned by the query. Used with PxHitBuffer.
\note If true (PxAgain) is returned from the callback, nbTouches will be reset to 0. */
PxU32 nbTouches;
/**
\brief Initializes the class with user provided buffer.
\param[in] aTouches Optional buffer for recording PxQueryHitType::eTOUCH type hits.
\param[in] aMaxNbTouches Size of touch buffer.
\note if aTouches is NULL and aMaxNbTouches is 0, only the closest blocking hit will be recorded by the query.
\note If PxQueryFlag::eANY_HIT flag is used as a query parameter, hasBlock will be set to true and blockingHit will be used to receive the result.
\note Both eTOUCH and eBLOCK hits will be registered as hasBlock=true and stored in PxHitCallback.block when eANY_HIT flag is used.
@see PxHitCallback.hasBlock PxHitCallback.block */
PxHitCallback(HitType* aTouches, PxU32 aMaxNbTouches)
: hasBlock(false), touches(aTouches), maxNbTouches(aMaxNbTouches), nbTouches(0)
{}
/**
\brief virtual callback function used to communicate query results to the user.
This callback will always be invoked with #touches as a buffer if #touches was specified as non-NULL.
All reported touch hits are guaranteed to be closer than the closest blocking hit.
\param[in] buffer Callback will report touch hits to the user in this buffer. This pointer will be the same as #touches.
\param[in] nbHits Number of touch hits reported in buffer. This number will not exceed #maxNbTouches.
\note There is a significant performance penalty in case multiple touch callbacks are issued (up to 2x)
\note to avoid the penalty use a bigger buffer so that all touching hits can be reported in a single buffer.
\note If true (again) is returned from the callback, nbTouches will be reset to 0,
\note If false is returned, nbTouched will remain unchanged.
\note By the time processTouches is first called, the globally closest blocking hit is already determined,
\note values of hasBlock and block are final and all touch hits are guaranteed to be closer than the blocking hit.
\note touches and maxNbTouches can be modified inside of processTouches callback.
\return true to continue receiving callbacks in case there are more hits or false to stop.
@see PxAgain PxRaycastHit PxSweepHit PxOverlapHit */
virtual PxAgain processTouches(const HitType* buffer, PxU32 nbHits) = 0;
virtual void finalizeQuery() {} //!< Query finalization callback, called after the last processTouches callback.
virtual ~PxHitCallback() {}
/** \brief Returns true if any blocking or touching hits were encountered during a query. */
PX_FORCE_INLINE bool hasAnyHits() { return (hasBlock || (nbTouches > 0)); }
};
/**
\brief Returns scene query hits (intersections) to the user in a preallocated buffer.
Will clip touch hits to maximum buffer capacity. When clipped, an arbitrary subset of touching hits will be discarded.
Overflow does not trigger warnings or errors. block and hasBlock will be valid in finalizeQuery callback and after query completion.
Touching hits are guaranteed to have closer or same distance ( <= condition) as the globally nearest blocking hit at the time any processTouches()
callback is issued.
\note Pre-made typedef shorthands, such as ::PxRaycastBuffer can be used for raycast, overlap and sweep queries.
@see PxHitCallback
@see PxRaycastBuffer PxOverlapBuffer PxSweepBuffer PxRaycastBufferN PxOverlapBufferN PxSweepBufferN
*/
template<typename HitType>
struct PxHitBuffer : public PxHitCallback<HitType>
{
/**
\brief Initializes the buffer with user memory.
The buffer is initialized with 0 touch hits by default => query will only report a single closest blocking hit.
Use PxQueryFlag::eANY_HIT to tell the query to abort and return any first hit encoutered as blocking.
\param[in] aTouches Optional buffer for recording PxQueryHitType::eTOUCH type hits.
\param[in] aMaxNbTouches Size of touch buffer.
@see PxHitCallback */
PxHitBuffer(HitType* aTouches = NULL, PxU32 aMaxNbTouches = 0) : PxHitCallback<HitType>(aTouches, aMaxNbTouches) {}
/** \brief Computes the number of any hits in this result, blocking or touching. */
PX_INLINE PxU32 getNbAnyHits() const { return getNbTouches() + PxU32(this->hasBlock); }
/** \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 < getNbTouches() + PxU32(this->hasBlock));
return index < getNbTouches() ? getTouches()[index] : this->block; }
PX_INLINE PxU32 getNbTouches() const { return this->nbTouches; }
PX_INLINE const HitType* getTouches() const { return this->touches; }
PX_INLINE const HitType& getTouch(const PxU32 index) const { PX_ASSERT(index < getNbTouches()); return getTouches()[index]; }
PX_INLINE PxU32 getMaxNbTouches() const { return this->maxNbTouches; }
virtual ~PxHitBuffer() {}
protected:
// stops after the first callback
virtual PxAgain processTouches(const HitType* buffer, PxU32 nbHits) { PX_UNUSED(buffer); PX_UNUSED(nbHits); return false; }
};
/** \brief Raycast query callback. */
typedef PxHitCallback<PxRaycastHit> PxRaycastCallback;
/** \brief Overlap query callback. */
typedef PxHitCallback<PxOverlapHit> PxOverlapCallback;
/** \brief Sweep query callback. */
typedef PxHitCallback<PxSweepHit> PxSweepCallback;
/** \brief Raycast query buffer. */
typedef PxHitBuffer<PxRaycastHit> PxRaycastBuffer;
/** \brief Overlap query buffer. */
typedef PxHitBuffer<PxOverlapHit> PxOverlapBuffer;
/** \brief Sweep query buffer. */
typedef PxHitBuffer<PxSweepHit> PxSweepBuffer;
/** \brief Returns touching raycast hits to the user in a fixed size array embedded in the buffer class. **/
template <int N>
struct PxRaycastBufferN : public PxHitBuffer<PxRaycastHit>
{
PxRaycastHit hits[N];
PxRaycastBufferN() : PxHitBuffer<PxRaycastHit>(hits, N) {}
};
/** \brief Returns touching overlap hits to the user in a fixed size array embedded in the buffer class. **/
template <int N>
struct PxOverlapBufferN : public PxHitBuffer<PxOverlapHit>
{
PxOverlapHit hits[N];
PxOverlapBufferN() : PxHitBuffer<PxOverlapHit>(hits, N) {}
};
/** \brief Returns touching sweep hits to the user in a fixed size array embedded in the buffer class. **/
template <int N>
struct PxSweepBufferN : public PxHitBuffer<PxSweepHit>
{
PxSweepHit hits[N];
PxSweepBufferN() : PxHitBuffer<PxSweepHit>(hits, N) {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,237 @@
//
// 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-2018 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_RIGIDACTOR
#define PX_PHYSICS_NX_RIGIDACTOR
/** \addtogroup physics
@{
*/
#include "PxActor.h"
#include "PxShape.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxConstraint;
class PxMaterial;
class PxGeometry;
class PxBVHStructure;
/**
\brief PxRigidActor represents a base class shared between dynamic and static rigid bodies in the physics SDK.
PxRigidActor objects specify the geometry of the object by defining a set of attached shapes (see #PxShape).
@see PxActor
*/
class PxRigidActor : public PxActor
{
public:
/**
\brief Deletes the rigid actor object.
Also releases any shapes associated with the actor.
Releasing an actor will affect any objects that are connected to the actor (constraint shaders like joints etc.).
Such connected objects will be deleted upon scene deletion, or explicitly by the user by calling release()
on these objects. It is recommended to always remove all objects that reference actors before the actors
themselves are removed. It is not possible to retrieve list of dead connected objects.
<b>Sleeping:</b> This call will awaken any sleeping actors contacting the deleted actor (directly or indirectly).
Calls #PxActor::release() so you might want to check the documentation of that method as well.
@see PxActor::release()
*/
virtual void release() = 0;
/************************************************************************************************/
/** @name Global Pose Manipulation
*/
/**
\brief Retrieves the actors world space transform.
The getGlobalPose() method retrieves the actor's current actor space to world space transformation.
\return Global pose of object.
@see PxRigidDynamic.setGlobalPose() PxRigidStatic.setGlobalPose()
*/
virtual PxTransform getGlobalPose() const = 0;
/**
\brief Method for setting an actor's pose in the world.
This method instantaneously changes the actor space to world space transformation.
This method is mainly for dynamic rigid bodies (see #PxRigidDynamic). Calling this method on static actors is
likely to result in a performance penalty, since internal optimization structures for static actors may need to be
recomputed. In addition, moving static actors will not interact correctly with dynamic actors or joints.
To directly control an actor's position and have it correctly interact with dynamic bodies and joints, create a dynamic
body with the PxRigidBodyFlag::eKINEMATIC flag, then use the setKinematicTarget() commands to define its path.
Even when moving dynamic actors, exercise restraint in making use of this method. Where possible, avoid:
\li moving actors into other actors, thus causing overlap (an invalid physical state)
\li moving an actor that is connected by a joint to another away from the other (thus causing joint error)
<b>Sleeping:</b> This call wakes dynamic actors if they are sleeping and the autowake parameter is true (default).
\param[in] pose Transformation from the actors local frame to the global frame. <b>Range:</b> rigid body transform.
\param[in] autowake whether to wake the object if it is dynamic. This parameter has no effect for static or kinematic actors. If true and the current wake counter value is smaller than #PxSceneDesc::wakeCounterResetValue it will get increased to the reset value.
@see getGlobalPose()
*/
virtual void setGlobalPose(const PxTransform& pose, bool autowake = true) = 0;
/************************************************************************************************/
/** @name Shapes
*/
/** attach a shared shape to an actor
This call will increment the reference count of the shape.
\note Mass properties of dynamic rigid actors will not automatically be recomputed
to reflect the new mass distribution implied by the shape. Follow this call with a call to
the PhysX extensions method #PxRigidBodyExt::updateMassAndInertia() to do that.
Attaching a triangle mesh, heightfield or plane geometry shape configured as eSIMULATION_SHAPE is not supported for
non-kinematic PxRigidDynamic instances.
<b>Sleeping:</b> Does <b>NOT</b> wake the actor up automatically.
\param[in] shape the shape to attach.
\return True if success.
*/
virtual bool attachShape(PxShape& shape) = 0;
/** detach a shape from an actor.
This will also decrement the reference count of the PxShape, and if the reference count is zero, will cause it to be deleted.
<b>Sleeping:</b> Does <b>NOT</b> wake the actor up automatically.
\param[in] shape the shape to detach.
\param[in] wakeOnLostTouch Specifies whether touching objects from the previous frame should get woken up in the next frame. Only applies to PxArticulation and PxRigidActor types.
*/
virtual void detachShape(PxShape& shape, bool wakeOnLostTouch = true) = 0;
/**
\brief Returns the number of shapes assigned to the actor.
You can use #getShapes() to retrieve the shape pointers.
\return Number of shapes associated with this actor.
@see PxShape getShapes()
*/
virtual PxU32 getNbShapes() const = 0;
/**
\brief Retrieve all the shape pointers belonging to the actor.
These are the shapes used by the actor for collision detection.
You can retrieve the number of shape pointers by calling #getNbShapes()
Note: Removing shapes with #PxShape::release() will invalidate the pointer of the released shape.
\param[out] userBuffer The buffer to store the shape pointers.
\param[in] bufferSize Size of provided user buffer.
\param[in] startIndex Index of first shape pointer to be retrieved
\return Number of shape pointers written to the buffer.
@see PxShape getNbShapes() PxShape::release()
*/
virtual PxU32 getShapes(PxShape** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
/************************************************************************************************/
/** @name Constraints
*/
/**
\brief Returns the number of constraint shaders attached to the actor.
You can use #getConstraints() to retrieve the constraint shader pointers.
\return Number of constraint shaders attached to this actor.
@see PxConstraint getConstraints()
*/
virtual PxU32 getNbConstraints() const = 0;
/**
\brief Retrieve all the constraint shader pointers belonging to the actor.
You can retrieve the number of constraint shader pointers by calling #getNbConstraints()
Note: Removing constraint shaders with #PxConstraint::release() will invalidate the pointer of the released constraint.
\param[out] userBuffer The buffer to store the constraint shader pointers.
\param[in] bufferSize Size of provided user buffer.
\param[in] startIndex Index of first constraint pointer to be retrieved
\return Number of constraint shader pointers written to the buffer.
@see PxConstraint getNbConstraints() PxConstraint::release()
*/
virtual PxU32 getConstraints(PxConstraint** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
protected:
PX_INLINE PxRigidActor(PxType concreteType, PxBaseFlags baseFlags) : PxActor(concreteType, baseFlags) {}
PX_INLINE PxRigidActor(PxBaseFlags baseFlags) : PxActor(baseFlags) {}
virtual ~PxRigidActor() {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxRigidActor", name) || PxActor::isKindOf(name); }
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,701 @@
//
// 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-2018 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_RIGIDBODY
#define PX_PHYSICS_NX_RIGIDBODY
/** \addtogroup physics
@{
*/
#include "PxRigidActor.h"
#include "PxForceMode.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Collection of flags describing the behavior of a rigid body.
@see PxRigidBody.setRigidBodyFlag(), PxRigidBody.getRigidBodyFlags()
*/
struct PxRigidBodyFlag
{
enum Enum
{
/**
\brief Enables kinematic mode for the actor.
Kinematic actors are special dynamic actors that are not
influenced by forces (such as gravity), and have no momentum. They are considered to have infinite
mass and can be moved around the world using the setKinematicTarget() method. They will push
regular dynamic actors out of the way. Kinematics will not collide with static or other kinematic objects.
Kinematic actors are great for moving platforms or characters, where direct motion control is desired.
You can not connect Reduced joints to kinematic actors. Lagrange joints work ok if the platform
is moving with a relatively low, uniform velocity.
<b>Sleeping:</b>
\li Setting this flag on a dynamic actor will put the actor to sleep and set the velocities to 0.
\li If this flag gets cleared, the current sleep state of the actor will be kept.
\note kinematic actors are incompatible with CCD so raising this flag will automatically clear eENABLE_CCD
@see PxRigidDynamic.setKinematicTarget()
*/
eKINEMATIC = (1<<0), //!< Enable kinematic mode for the body.
/**
\brief Use the kinematic target transform for scene queries.
If this flag is raised, then scene queries will treat the kinematic target transform as the current pose
of the body (instead of using the actual pose). Without this flag, the kinematic target will only take
effect with respect to scene queries after a simulation step.
@see PxRigidDynamic.setKinematicTarget()
*/
eUSE_KINEMATIC_TARGET_FOR_SCENE_QUERIES = (1<<1),
/**
\brief Enables swept integration for the actor.
If this flag is raised and CCD is enabled on the scene, then this body will be simulated by the CCD system to ensure that collisions are not missed due to
high-speed motion. Note individual shape pairs still need to enable PxPairFlag::eDETECT_CCD_CONTACT in the collision filtering to enable the CCD to respond to
individual interactions.
\note kinematic actors are incompatible with CCD so this flag will be cleared automatically when raised on a kinematic actor
*/
eENABLE_CCD = (1<<2), //!< Enable CCD for the body.
/**
\brief Enabled CCD in swept integration for the actor.
If this flag is raised and CCD is enabled, CCD interactions will simulate friction. By default, friction is disabled in CCD interactions because
CCD friction has been observed to introduce some simulation artifacts. CCD friction was enabled in previous versions of the SDK. Raising this flag will result in behavior
that is a closer match for previous versions of the SDK.
\note This flag requires PxRigidBodyFlag::eENABLE_CCD to be raised to have any effect.
*/
eENABLE_CCD_FRICTION = (1<<3),
/**
\brief Register a rigid body for reporting pose changes by the simulation at an early stage.
Sometimes it might be advantageous to get access to the new pose of a rigid body as early as possible and
not wait until the call to fetchResults() returns. Setting this flag will schedule the rigid body to get reported
in #PxSimulationEventCallback::onAdvance(). Please refer to the documentation of that callback to understand
the behavior and limitations of this functionality.
@see PxSimulationEventCallback::onAdvance()
*/
eENABLE_POSE_INTEGRATION_PREVIEW = (1 << 4),
/**
\brief Register a rigid body to dynamicly adjust contact offset based on velocity. This can be used to achieve a CCD effect.
*/
eENABLE_SPECULATIVE_CCD = (1 << 5),
/**
\brief Permit CCD to limit maxContactImpulse. This is useful for use-cases like a destruction system but can cause visual artefacts so is not enabled by default.
*/
eENABLE_CCD_MAX_CONTACT_IMPULSE = (1 << 6),
/**
\brief Carries over forces/accelerations between frames, rather than clearning them
*/
eRETAIN_ACCELERATIONS = (1<<7)
};
};
/**
\brief collection of set bits defined in PxRigidBodyFlag.
@see PxRigidBodyFlag
*/
typedef PxFlags<PxRigidBodyFlag::Enum,PxU8> PxRigidBodyFlags;
PX_FLAGS_OPERATORS(PxRigidBodyFlag::Enum,PxU8)
/**
\brief PxRigidBody is a base class shared between dynamic rigid body objects.
@see PxRigidActor
*/
class PxRigidBody : public PxRigidActor
{
public:
// Runtime modifications
/************************************************************************************************/
/** @name Mass Manipulation
*/
/**
\brief Sets the pose of the center of mass relative to the actor.
\note Changing this transform will not move the actor in the world!
\note Setting an unrealistic center of mass which is a long way from the body can make it difficult for
the SDK to solve constraints. Perhaps leading to instability and jittering bodies.
<b>Default:</b> the identity transform
\param[in] pose Mass frame offset transform relative to the actor frame. <b>Range:</b> rigid body transform.
@see getCMassLocalPose() PxRigidBodyDesc.massLocalPose
*/
virtual void setCMassLocalPose(const PxTransform& pose) = 0;
/**
\brief Retrieves the center of mass pose relative to the actor frame.
\return The center of mass pose relative to the actor frame.
@see setCMassLocalPose() PxRigidBodyDesc.massLocalPose
*/
virtual PxTransform getCMassLocalPose() const = 0;
/**
\brief Sets the mass of a dynamic actor.
The mass must be non-negative.
setMass() does not update the inertial properties of the body, to change the inertia tensor
use setMassSpaceInertiaTensor() or the PhysX extensions method #PxRigidBodyExt::updateMassAndInertia().
\note A value of 0 is interpreted as infinite mass.
\note Values of 0 are not permitted for instances of PxArticulationLink but are permitted for instances of PxRigidDynamic.
<b>Default:</b> 1.0
<b>Sleeping:</b> Does <b>NOT</b> wake the actor up automatically.
\param[in] mass New mass value for the actor. <b>Range:</b> [0, PX_MAX_F32)
@see getMass() PxRigidBodyDesc.mass setMassSpaceInertiaTensor()
*/
virtual void setMass(PxReal mass) = 0;
/**
\brief Retrieves the mass of the actor.
\note A value of 0 is interpreted as infinite mass.
\return The mass of this actor.
@see setMass() PxRigidBodyDesc.mass setMassSpaceInertiaTensor()
*/
virtual PxReal getMass() const = 0;
/**
\brief Retrieves the inverse mass of the actor.
\return The inverse mass of this actor.
@see setMass() PxRigidBodyDesc.mass setMassSpaceInertiaTensor()
*/
virtual PxReal getInvMass() const = 0;
/**
\brief Sets the inertia tensor, using a parameter specified in mass space coordinates.
Note that such matrices are diagonal -- the passed vector is the diagonal.
If you have a non diagonal world/actor space inertia tensor(3x3 matrix). Then you need to
diagonalize it and set an appropriate mass space transform. See #setCMassLocalPose().
The inertia tensor elements must be non-negative.
\note A value of 0 in an element is interpreted as infinite inertia along that axis.
\note Values of 0 are not permitted for instances of PxArticulationLink but are permitted for instances of PxRigidDynamic.
<b>Default:</b> (1.0, 1.0, 1.0)
<b>Sleeping:</b> Does <b>NOT</b> wake the actor up automatically.
\param[in] m New mass space inertia tensor for the actor.
@see PxRigidBodyDesc.massSpaceInertia getMassSpaceInertia() setMass() setCMassLocalPose()
*/
virtual void setMassSpaceInertiaTensor(const PxVec3& m) = 0;
/**
\brief Retrieves the diagonal inertia tensor of the actor relative to the mass coordinate frame.
This method retrieves a mass frame inertia vector.
\return The mass space inertia tensor of this actor.
\note A value of 0 in an element is interpreted as infinite inertia along that axis.
@see PxRigidBodyDesc.massSpaceInertia setMassSpaceInertiaTensor() setMass() setCMassLocalPose()
*/
virtual PxVec3 getMassSpaceInertiaTensor() const = 0;
/**
\brief Retrieves the diagonal inverse inertia tensor of the actor relative to the mass coordinate frame.
This method retrieves a mass frame inverse inertia vector.
\note A value of 0 in an element is interpreted as infinite inertia along that axis.
\return The mass space inverse inertia tensor of this actor.
@see PxRigidBodyDesc.massSpaceInertia setMassSpaceInertiaTensor() setMass() setCMassLocalPose()
*/
virtual PxVec3 getMassSpaceInvInertiaTensor() const = 0;
/************************************************************************************************/
/** @name Damping
*/
/**
\brief Sets the linear damping coefficient.
Zero represents no damping. The damping coefficient must be nonnegative.
<b>Default:</b> 0.0
\param[in] linDamp Linear damping coefficient. <b>Range:</b> [0, PX_MAX_F32)
@see getLinearDamping() setAngularDamping()
*/
virtual void setLinearDamping(PxReal linDamp) = 0;
/**
\brief Retrieves the linear damping coefficient.
\return The linear damping coefficient associated with this actor.
@see setLinearDamping() getAngularDamping()
*/
virtual PxReal getLinearDamping() const = 0;
/**
\brief Sets the angular damping coefficient.
Zero represents no damping.
The angular damping coefficient must be nonnegative.
<b>Default:</b> 0.05
\param[in] angDamp Angular damping coefficient. <b>Range:</b> [0, PX_MAX_F32)
@see getAngularDamping() setLinearDamping()
*/
virtual void setAngularDamping(PxReal angDamp) = 0;
/**
\brief Retrieves the angular damping coefficient.
\return The angular damping coefficient associated with this actor.
@see setAngularDamping() getLinearDamping()
*/
virtual PxReal getAngularDamping() const = 0;
/************************************************************************************************/
/** @name Velocity
*/
/**
\brief Retrieves the linear velocity of an actor.
\return The linear velocity of the actor.
@see PxRigidDynamic.setLinearVelocity() getAngularVelocity()
*/
virtual PxVec3 getLinearVelocity() const = 0;
/**
\brief Sets the linear velocity of the actor.
Note that if you continuously set the velocity of an actor yourself,
forces such as gravity or friction will not be able to manifest themselves, because forces directly
influence only the velocity/momentum of an actor.
<b>Default:</b> (0.0, 0.0, 0.0)
<b>Sleeping:</b> This call wakes the actor if it is sleeping, the autowake parameter is true (default) or the
new velocity is non-zero
\note It is invalid to use this method if PxActorFlag::eDISABLE_SIMULATION is set.
\param[in] linVel New linear velocity of actor. <b>Range:</b> velocity vector
\param[in] autowake Whether to wake the object up if it is asleep and the velocity is non-zero. If true and the current wake counter value is smaller than #PxSceneDesc::wakeCounterResetValue it will get increased to the reset value.
@see getLinearVelocity() setAngularVelocity()
*/
virtual void setLinearVelocity(const PxVec3& linVel, bool autowake = true ) = 0;
/**
\brief Retrieves the angular velocity of the actor.
\return The angular velocity of the actor.
@see PxRigidDynamic.setAngularVelocity() getLinearVelocity()
*/
virtual PxVec3 getAngularVelocity() const = 0;
/**
\brief Sets the angular velocity of the actor.
Note that if you continuously set the angular velocity of an actor yourself,
forces such as friction will not be able to rotate the actor, because forces directly influence only the velocity/momentum.
<b>Default:</b> (0.0, 0.0, 0.0)
<b>Sleeping:</b> This call wakes the actor if it is sleeping, the autowake parameter is true (default) or the
new velocity is non-zero
\note It is invalid to use this method if PxActorFlag::eDISABLE_SIMULATION is set.
\param[in] angVel New angular velocity of actor. <b>Range:</b> angular velocity vector
\param[in] autowake Whether to wake the object up if it is asleep and the velocity is non-zero. If true and the current wake
counter value is smaller than #PxSceneDesc::wakeCounterResetValue it will get increased to the reset value.
@see getAngularVelocity() setLinearVelocity()
*/
virtual void setAngularVelocity(const PxVec3& angVel, bool autowake = true ) = 0;
/**
\brief Lets you set the maximum angular velocity permitted for this actor.
For various internal computations, very quickly rotating actors introduce error
into the simulation, which leads to undesired results.
With this function, you can set the maximum angular velocity permitted for this rigid body.
Higher angular velocities are clamped to this value.
Note: The angular velocity is clamped to the set value <i>before</i> the solver, which means that
the limit may still be momentarily exceeded.
<b>Default:</b> 100.0
\param[in] maxAngVel Max allowable angular velocity for actor. <b>Range:</b> [0, PX_MAX_F32)
@see getMaxAngularVelocity()
*/
virtual void setMaxAngularVelocity(PxReal maxAngVel) = 0;
/**
\brief Retrieves the maximum angular velocity permitted for this actor.
\return The maximum allowed angular velocity for this actor.
@see setMaxAngularVelocity
*/
virtual PxReal getMaxAngularVelocity() const = 0;
/**
\brief Lets you set the maximum linear velocity permitted for this actor.
With this function, you can set the maximum linear velocity permitted for this rigid body.
Higher angular velocities are clamped to this value.
Note: The angular velocity is clamped to the set value <i>before</i> the solver, which means that
the limit may still be momentarily exceeded.
<b>Default:</b> PX_MAX_F32
\param[in] maxLinVel Max allowable linear velocity for actor. <b>Range:</b> [0, PX_MAX_F32)
@see getMaxAngularVelocity()
*/
virtual void setMaxLinearVelocity(PxReal maxLinVel) = 0;
/**
\brief Retrieves the maximum angular velocity permitted for this actor.
\return The maximum allowed angular velocity for this actor.
@see setMaxLinearVelocity
*/
virtual PxReal getMaxLinearVelocity() const = 0;
/************************************************************************************************/
/** @name Forces
*/
/**
\brief Applies a force (or impulse) defined in the global coordinate frame to the actor at its center of mass.
<b>This will not induce a torque</b>.
::PxForceMode determines if the force is to be conventional or impulsive.
Each actor has an acceleration and a velocity change accumulator which are directly modified using the modes PxForceMode::eACCELERATION
and PxForceMode::eVELOCITY_CHANGE respectively. The modes PxForceMode::eFORCE and PxForceMode::eIMPULSE also modify these same
accumulators and are just short hand for multiplying the vector parameter by inverse mass and then using PxForceMode::eACCELERATION and
PxForceMode::eVELOCITY_CHANGE respectively.
\note It is invalid to use this method if the actor has not been added to a scene already or if PxActorFlag::eDISABLE_SIMULATION is set.
\note The force modes PxForceMode::eIMPULSE and PxForceMode::eVELOCITY_CHANGE can not be applied to articulation links.
\note if this is called on an articulation link, only the link is updated, not the entire articulation.
\note see #PxRigidBodyExt::computeVelocityDeltaFromImpulse for details of how to compute the change in linear velocity that
will arise from the application of an impulsive force, where an impulsive force is applied force multiplied by a timestep.
<b>Sleeping:</b> This call wakes the actor if it is sleeping and the autowake parameter is true (default) or the force is non-zero.
\param[in] force Force/Impulse to apply defined in the global frame.
\param[in] mode The mode to use when applying the force/impulse(see #PxForceMode)
\param[in] autowake Specify if the call should wake up the actor if it is currently asleep. If true and the current wake counter value is smaller than #PxSceneDesc::wakeCounterResetValue it will get increased to the reset value.
@see PxForceMode addTorque
*/
virtual void addForce(const PxVec3& force, PxForceMode::Enum mode = PxForceMode::eFORCE, bool autowake = true) = 0;
/**
\brief Applies an impulsive torque defined in the global coordinate frame to the actor.
::PxForceMode determines if the torque is to be conventional or impulsive.
Each actor has an angular acceleration and an angular velocity change accumulator which are directly modified using the modes
PxForceMode::eACCELERATION and PxForceMode::eVELOCITY_CHANGE respectively. The modes PxForceMode::eFORCE and PxForceMode::eIMPULSE
also modify these same accumulators and are just short hand for multiplying the vector parameter by inverse inertia and then
using PxForceMode::eACCELERATION and PxForceMode::eVELOCITY_CHANGE respectively.
\note It is invalid to use this method if the actor has not been added to a scene already or if PxActorFlag::eDISABLE_SIMULATION is set.
\note The force modes PxForceMode::eIMPULSE and PxForceMode::eVELOCITY_CHANGE can not be applied to articulation links.
\note if this called on an articulation link, only the link is updated, not the entire articulation.
\note see #PxRigidBodyExt::computeVelocityDeltaFromImpulse for details of how to compute the change in angular velocity that
will arise from the application of an impulsive torque, where an impulsive torque is an applied torque multiplied by a timestep.
<b>Sleeping:</b> This call wakes the actor if it is sleeping and the autowake parameter is true (default) or the torque is non-zero.
\param[in] torque Torque to apply defined in the global frame. <b>Range:</b> torque vector
\param[in] mode The mode to use when applying the force/impulse(see #PxForceMode).
\param[in] autowake whether to wake up the object if it is asleep. If true and the current wake counter value is smaller than #PxSceneDesc::wakeCounterResetValue it will get increased to the reset value.
@see PxForceMode addForce()
*/
virtual void addTorque(const PxVec3& torque, PxForceMode::Enum mode = PxForceMode::eFORCE, bool autowake = true) = 0;
/**
\brief Clears the accumulated forces (sets the accumulated force back to zero).
Each actor has an acceleration and a velocity change accumulator which are directly modified using the modes PxForceMode::eACCELERATION
and PxForceMode::eVELOCITY_CHANGE respectively. The modes PxForceMode::eFORCE and PxForceMode::eIMPULSE also modify these same
accumulators (see PxRigidBody::addForce() for details); therefore the effect of calling clearForce(PxForceMode::eFORCE) is equivalent to calling
clearForce(PxForceMode::eACCELERATION), and the effect of calling clearForce(PxForceMode::eIMPULSE) is equivalent to calling
clearForce(PxForceMode::eVELOCITY_CHANGE).
::PxForceMode determines if the cleared force is to be conventional or impulsive.
\note The force modes PxForceMode::eIMPULSE and PxForceMode::eVELOCITY_CHANGE can not be applied to articulation links.
\note It is invalid to use this method if the actor has not been added to a scene already or if PxActorFlag::eDISABLE_SIMULATION is set.
\param[in] mode The mode to use when clearing the force/impulse(see #PxForceMode)
@see PxForceMode addForce
*/
virtual void clearForce(PxForceMode::Enum mode = PxForceMode::eFORCE) = 0;
/**
\brief Clears the impulsive torque defined in the global coordinate frame to the actor.
::PxForceMode determines if the cleared torque is to be conventional or impulsive.
Each actor has an angular acceleration and a velocity change accumulator which are directly modified using the modes PxForceMode::eACCELERATION
and PxForceMode::eVELOCITY_CHANGE respectively. The modes PxForceMode::eFORCE and PxForceMode::eIMPULSE also modify these same
accumulators (see PxRigidBody::addTorque() for details); therefore the effect of calling clearTorque(PxForceMode::eFORCE) is equivalent to calling
clearTorque(PxForceMode::eACCELERATION), and the effect of calling clearTorque(PxForceMode::eIMPULSE) is equivalent to calling
clearTorque(PxForceMode::eVELOCITY_CHANGE).
\note The force modes PxForceMode::eIMPULSE and PxForceMode::eVELOCITY_CHANGE can not be applied to articulation links.
\note It is invalid to use this method if the actor has not been added to a scene already or if PxActorFlag::eDISABLE_SIMULATION is set.
\param[in] mode The mode to use when clearing the force/impulse(see #PxForceMode).
@see PxForceMode addTorque
*/
virtual void clearTorque(PxForceMode::Enum mode = PxForceMode::eFORCE) = 0;
/**
\brief Sets the impulsive force and torque defined in the global coordinate frame to the actor.
::PxForceMode determines if the cleared torque is to be conventional or impulsive.
\note The force modes PxForceMode::eIMPULSE and PxForceMode::eVELOCITY_CHANGE can not be applied to articulation links.
\note It is invalid to use this method if the actor has not been added to a scene already or if PxActorFlag::eDISABLE_SIMULATION is set.
@see PxForceMode addTorque
*/
virtual void setForceAndTorque(const PxVec3& force, const PxVec3& torque, PxForceMode::Enum mode = PxForceMode::eFORCE) = 0;
/**
\brief Raises or clears a particular rigid body flag.
See the list of flags #PxRigidBodyFlag
<b>Default:</b> no flags are set
<b>Sleeping:</b> Does <b>NOT</b> wake the actor up automatically.
\param[in] flag The PxRigidBody flag to raise(set) or clear. See #PxRigidBodyFlag.
\param[in] value The new boolean value for the flag.
@see PxRigidBodyFlag getRigidBodyFlags()
*/
virtual void setRigidBodyFlag(PxRigidBodyFlag::Enum flag, bool value) = 0;
virtual void setRigidBodyFlags(PxRigidBodyFlags inFlags) = 0;
/**
\brief Reads the PxRigidBody flags.
See the list of flags #PxRigidBodyFlag
\return The values of the PxRigidBody flags.
@see PxRigidBodyFlag setRigidBodyFlag()
*/
virtual PxRigidBodyFlags getRigidBodyFlags() const = 0;
/**
\brief Sets the CCD minimum advance coefficient.
The CCD minimum advance coefficient is a value in the range [0, 1] that is used to control the minimum amount of time a body is integrated when
it has a CCD contact. The actual minimum amount of time that is integrated depends on various properties, including the relative speed and collision shapes
of the bodies involved in the contact. From these properties, a numeric value is calculated that determines the maximum distance (and therefore maximum time)
which these bodies could be integrated forwards that would ensure that these bodies did not pass through each-other. This value is then scaled by CCD minimum advance
coefficient to determine the amount of time that will be consumed in the CCD pass.
<b>Things to consider:</b>
A large value (approaching 1) ensures that the objects will always advance some time. However, larger values increase the chances of objects gently drifting through each-other in
scenes which the constraint solver can't converge, e.g. scenes where an object is being dragged through a wall with a constraint.
A value of 0 ensures that the pair of objects stop at the exact time-of-impact and will not gently drift through each-other. However, with very small/thin objects initially in
contact, this can lead to a large amount of time being dropped and increases the chances of jamming. Jamming occurs when the an object is persistently in contact with an object
such that the time-of-impact is 0, which results in no time being advanced for those objects in that CCD pass.
The chances of jamming can be reduced by increasing the number of CCD mass @see PxSceneDesc.ccdMaxPasses. However, increasing this number increases the CCD overhead.
\param[in] advanceCoefficient The CCD min advance coefficient. <b>Range:</b> [0, 1] <b>Default:</b> 0.15
*/
virtual void setMinCCDAdvanceCoefficient(PxReal advanceCoefficient) = 0;
/**
\brief Gets the CCD minimum advance coefficient.
\return The value of the CCD min advance coefficient.
@see setMinCCDAdvanceCoefficient
*/
virtual PxReal getMinCCDAdvanceCoefficient() const = 0;
/**
\brief Sets the maximum depenetration velocity permitted to be introduced by the solver.
This value controls how much velocity the solver can introduce to correct for penetrations in contacts.
\param[in] biasClamp The maximum velocity to de-penetrate by <b>Range:</b> (0, PX_MAX_F32].
*/
virtual void setMaxDepenetrationVelocity(PxReal biasClamp) = 0;
/**
\brief Returns the maximum depenetration velocity the solver is permitted to introduced.
This value controls how much velocity the solver can introduce to correct for penetrations in contacts.
\return The maximum penetration bias applied by the solver.
*/
virtual PxReal getMaxDepenetrationVelocity() const = 0;
/**
\brief Sets a limit on the impulse that may be applied at a contact. The maximum impulse at a contact between two dynamic or kinematic
bodies will be the minimum of the two limit values. For a collision between a static and a dynamic body, the impulse is limited
by the value for the dynamic body.
\param[in] maxImpulse the maximum contact impulse. <b>Range:</b> [0, PX_MAX_F32] <b>Default:</b> PX_MAX_F32
@see getMaxContactImpulse
*/
virtual void setMaxContactImpulse(PxReal maxImpulse) = 0;
/**
\brief Returns the maximum impulse that may be applied at a contact.
\return The maximum impulse that may be applied at a contact
@see setMaxContactImpulse
*/
virtual PxReal getMaxContactImpulse() const = 0;
/**
\brief Returns the island node index that only for internal use only
\return The island node index that only for internal use only
*/
virtual PxU32 getInternalIslandNodeIndex() const = 0;
protected:
PX_INLINE PxRigidBody(PxType concreteType, PxBaseFlags baseFlags) : PxRigidActor(concreteType, baseFlags) {}
PX_INLINE PxRigidBody(PxBaseFlags baseFlags) : PxRigidActor(baseFlags) {}
virtual ~PxRigidBody() {}
virtual bool isKindOf(const char* name)const { return !::strcmp("PxRigidBody", name) || PxRigidActor::isKindOf(name); }
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,388 @@
//
// 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-2018 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_RIGIDDYNAMIC
#define PX_PHYSICS_NX_RIGIDDYNAMIC
/** \addtogroup physics
@{
*/
#include "PxRigidBody.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Collection of flags providing a mechanism to lock motion along/around a specific axis.
@see PxRigidDynamic.setRigidDynamicLockFlag(), PxRigidBody.getRigidDynamicLockFlags()
*/
struct PxRigidDynamicLockFlag
{
enum Enum
{
eLOCK_LINEAR_X = (1 << 0),
eLOCK_LINEAR_Y = (1 << 1),
eLOCK_LINEAR_Z = (1 << 2),
eLOCK_ANGULAR_X = (1 << 3),
eLOCK_ANGULAR_Y = (1 << 4),
eLOCK_ANGULAR_Z = (1 << 5)
};
};
typedef PxFlags<PxRigidDynamicLockFlag::Enum, PxU16> PxRigidDynamicLockFlags;
PX_FLAGS_OPERATORS(PxRigidDynamicLockFlag::Enum, PxU16)
/**
\brief PxRigidDynamic represents a dynamic rigid simulation object in the physics SDK.
<h3>Creation</h3>
Instances of this class are created by calling #PxPhysics::createRigidDynamic() and deleted with #release().
<h3>Visualizations</h3>
\li #PxVisualizationParameter::eACTOR_AXES
\li #PxVisualizationParameter::eBODY_AXES
\li #PxVisualizationParameter::eBODY_MASS_AXES
\li #PxVisualizationParameter::eBODY_LIN_VELOCITY
\li #PxVisualizationParameter::eBODY_ANG_VELOCITY
@see PxRigidBody PxPhysics.createRigidDynamic() release()
*/
class PxRigidDynamic : public PxRigidBody
{
public:
// Runtime modifications
/************************************************************************************************/
/** @name Kinematic Actors
*/
/**
\brief Moves kinematically controlled dynamic actors through the game world.
You set a dynamic actor to be kinematic using the PxRigidBodyFlag::eKINEMATIC flag
with setRigidBodyFlag().
The move command will result in a velocity that will move the body into
the desired pose. After the move is carried out during a single time step,
the velocity is returned to zero. Thus, you must continuously call
this in every time step for kinematic actors so that they move along a path.
This function simply stores the move destination until the next simulation
step is processed, so consecutive calls will simply overwrite the stored target variable.
The motion is always fully carried out.
\note It is invalid to use this method if the actor has not been added to a scene already or if PxActorFlag::eDISABLE_SIMULATION is set.
<b>Sleeping:</b> This call wakes the actor if it is sleeping and will set the wake counter to #PxSceneDesc::wakeCounterResetValue.
\param[in] destination The desired pose for the kinematic actor, in the global frame. <b>Range:</b> rigid body transform.
@see getKinematicTarget() PxRigidBodyFlag setRigidBodyFlag()
*/
virtual void setKinematicTarget(const PxTransform& destination) = 0;
/**
\brief Get target pose of a kinematically controlled dynamic actor.
\param[out] target Transform to write the target pose to. Only valid if the method returns true.
\return True if the actor is a kinematically controlled dynamic and the target has been set, else False.
@see setKinematicTarget() PxRigidBodyFlag setRigidBodyFlag()
*/
virtual bool getKinematicTarget(PxTransform& target) const = 0;
/************************************************************************************************/
/** @name Sleeping
*/
/**
\brief Returns true if this body 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 one of its properties is changed by the user, the entire sleep mechanism should be transparent to the user.
In general, a dynamic rigid actor 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 is non-zero.
\li A non-zero force or torque has been applied.
If a dynamic rigid actor is sleeping, the following state is guaranteed:
\li The wake counter is zero.
\li The linear and angular velocity is zero.
\li There is no force update pending.
When an actor 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 actor is asleep after the call to PxScene::fetchResults() returns, it is guaranteed that the pose of the actor
was not changed. You can use this information to avoid updating the transforms of associated objects.
\note A kinematic actor is asleep unless a target pose has been set (in which case it will stay awake until the end of the next
simulation step where no target pose has been set anymore). The wake counter will get set to zero or to the reset value
#PxSceneDesc::wakeCounterResetValue in the case where a target pose has been set to be consistent with the definitions above.
\note It is invalid to use this method if the actor has not been added to a scene already.
\return True if the actor is sleeping.
@see isSleeping() wakeUp() putToSleep() getSleepThreshold()
*/
virtual bool isSleeping() const = 0;
/**
\brief Sets the mass-normalized kinetic energy threshold below which an actor may go to sleep.
Actors whose kinetic energy divided by their mass is below this threshold will be candidates for sleeping.
<b>Default:</b> 5e-5f * PxTolerancesScale::speed * PxTolerancesScale::speed
\param[in] threshold Energy below which an actor may go to sleep. <b>Range:</b> [0, PX_MAX_F32)
@see isSleeping() getSleepThreshold() wakeUp() putToSleep() PxTolerancesScale
*/
virtual void setSleepThreshold(PxReal threshold) = 0;
/**
\brief Returns the mass-normalized kinetic energy below which an actor 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 actor may participate in stabilization.
Actors 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> 1e-5f * 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 actor may participate in stabilization.
Actors 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 Reads the PxRigidDynamic lock flags.
See the list of flags #PxRigidDynamicLockFlag
\return The values of the PxRigidDynamicLock flags.
@see PxRigidDynamicLockFlag setRigidDynamicLockFlag()
*/
virtual PxRigidDynamicLockFlags getRigidDynamicLockFlags() const = 0;
/**
\brief Raises or clears a particular rigid dynamic lock flag.
See the list of flags #PxRigidDynamicLockFlag
<b>Default:</b> no flags are set
\param[in] flag The PxRigidDynamicLockBody flag to raise(set) or clear. See #PxRigidBodyFlag.
\param[in] value The new boolean value for the flag.
@see PxRigidDynamicLockFlag getRigidDynamicLockFlags()
*/
virtual void setRigidDynamicLockFlag(PxRigidDynamicLockFlag::Enum flag, bool value) = 0;
virtual void setRigidDynamicLockFlags(PxRigidDynamicLockFlags flags) = 0;
/**
\brief Sets the wake counter for the actor.
The wake counter value determines the minimum amount of time until the body can be put to sleep. Please note
that a body will not be put to sleep if the energy is above the specified threshold (see #setSleepThreshold())
or if other awake bodies are touching it.
\note Passing in a positive value will wake the actor up automatically.
\note It is invalid to use this method for kinematic actors since the wake counter for kinematics is defined
based on whether a target pose has been set (see the comment in #isSleeping()).
\note It is invalid to use this method if PxActorFlag::eDISABLE_SIMULATION is set.
<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 actor.
\return The wake counter of the actor.
@see isSleeping() setWakeCounter()
*/
virtual PxReal getWakeCounter() const = 0;
/**
\brief Wakes up the actor if it is sleeping.
The actor will get woken up and might cause other touching actors to wake up as well during the next simulation step.
\note This will set the wake counter of the actor to the value specified in #PxSceneDesc::wakeCounterResetValue.
\note It is invalid to use this method if the actor has not been added to a scene already or if PxActorFlag::eDISABLE_SIMULATION is set.
\note It is invalid to use this method for kinematic actors since the sleep state for kinematics is defined
based on whether a target pose has been set (see the comment in #isSleeping()).
@see isSleeping() putToSleep()
*/
virtual void wakeUp() = 0;
/**
\brief Forces the actor to sleep.
The actor will stay asleep during the next simulation step if not touched by another non-sleeping actor.
\note Any applied force will be cleared and the velocity and the wake counter of the actor will be set to 0.
\note It is invalid to use this method if the actor has not been added to a scene already or if PxActorFlag::eDISABLE_SIMULATION is set.
\note It is invalid to use this method for kinematic actors since the sleep state for kinematics is defined
based on whether a target pose has been set (see the comment in #isSleeping()).
@see isSleeping() wakeUp()
*/
virtual void putToSleep() = 0;
/************************************************************************************************/
/**
\brief Sets the solver iteration counts for the body.
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.
<b>Default:</b> 4 position iterations, 1 velocity iteration
\param[in] minPositionIters Number of position iterations the solver should perform for this body. <b>Range:</b> [1,255]
\param[in] minVelocityIters Number of velocity iterations the solver should perform for this body. <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 Retrieves the force threshold for contact reports.
The contact report threshold is a force threshold. If the force between
two actors exceeds this threshold for either of the two actors, a contact report
will be generated according to the contact report threshold flags provided by
the filter shader/callback.
See #PxPairFlag.
The threshold used for a collision between a dynamic actor and the static environment is
the threshold of the dynamic actor, and all contacts with static actors are summed to find
the total normal force.
<b>Default:</b> PX_MAX_F32
\return Force threshold for contact reports.
@see setContactReportThreshold PxPairFlag PxSimulationFilterShader PxSimulationFilterCallback
*/
virtual PxReal getContactReportThreshold() const = 0;
/**
\brief Sets the force threshold for contact reports.
See #getContactReportThreshold().
\param[in] threshold Force threshold for contact reports. <b>Range:</b> [0, PX_MAX_F32)
@see getContactReportThreshold PxPairFlag
*/
virtual void setContactReportThreshold(PxReal threshold) = 0;
virtual const char* getConcreteTypeName() const { return "PxRigidDynamic"; }
protected:
PX_INLINE PxRigidDynamic(PxType concreteType, PxBaseFlags baseFlags) : PxRigidBody(concreteType, baseFlags) {}
PX_INLINE PxRigidDynamic(PxBaseFlags baseFlags) : PxRigidBody(baseFlags) {}
virtual ~PxRigidDynamic() {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxRigidDynamic", name) || PxRigidBody::isKindOf(name); }
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,77 @@
//
// 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-2018 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_RIGIDSTATIC
#define PX_PHYSICS_NX_RIGIDSTATIC
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "PxRigidActor.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief PxRigidStatic represents a static rigid body simulation object in the physics SDK.
PxRigidStatic objects are static rigid physics entities. They shall be used to define solid objects which are fixed in the world.
<h3>Creation</h3>
Instances of this class are created by calling #PxPhysics::createRigidStatic() and deleted with #release().
<h3>Visualizations</h3>
\li #PxVisualizationParameter::eACTOR_AXES
@see PxRigidActor PxPhysics.createRigidStatic() release()
*/
class PxRigidStatic : public PxRigidActor
{
public:
virtual const char* getConcreteTypeName() const { return "PxRigidStatic"; }
protected:
PX_INLINE PxRigidStatic(PxType concreteType, PxBaseFlags baseFlags) : PxRigidActor(concreteType, baseFlags) {}
PX_INLINE PxRigidStatic(PxBaseFlags baseFlags) : PxRigidActor(baseFlags) {}
virtual ~PxRigidStatic() {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxRigidStatic", name) || PxRigidActor::isKindOf(name); }
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,129 @@
//
// 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-2018 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_SCENELOCK
#define PX_PHYSICS_NX_SCENELOCK
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "PxScene.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief RAII wrapper for the PxScene read lock.
Use this class as follows to lock the scene for reading by the current thread
for the duration of the enclosing scope:
PxSceneReadLock lock(sceneRef);
\see PxScene::lockRead(), PxScene::unlockRead(), PxSceneFlag::eREQUIRE_RW_LOCK
*/
class PxSceneReadLock
{
PxSceneReadLock(const PxSceneReadLock&);
PxSceneReadLock& operator=(const PxSceneReadLock&);
public:
/**
\brief Constructor
\param scene The scene to lock for reading
\param file Optional string for debugging purposes
\param line Optional line number for debugging purposes
*/
PxSceneReadLock(PxScene& scene, const char* file=NULL, PxU32 line=0)
: mScene(scene)
{
mScene.lockRead(file, line);
}
~PxSceneReadLock()
{
mScene.unlockRead();
}
private:
PxScene& mScene;
};
/**
\brief RAII wrapper for the PxScene write lock.
Use this class as follows to lock the scene for writing by the current thread
for the duration of the enclosing scope:
PxSceneWriteLock lock(sceneRef);
\see PxScene::lockWrite(), PxScene::unlockWrite(), PxSceneFlag::eREQUIRE_RW_LOCK
*/
class PxSceneWriteLock
{
PxSceneWriteLock(const PxSceneWriteLock&);
PxSceneWriteLock& operator=(const PxSceneWriteLock&);
public:
/**
\brief Constructor
\param scene The scene to lock for writing
\param file Optional string for debugging purposes
\param line Optional line number for debugging purposes
*/
PxSceneWriteLock(PxScene& scene, const char* file=NULL, PxU32 line=0)
: mScene(scene)
{
mScene.lockWrite(file, line);
}
~PxSceneWriteLock()
{
mScene.unlockWrite();
}
private:
PxScene& mScene;
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,639 @@
//
// 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-2018 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_SHAPE
#define PX_PHYSICS_NX_SHAPE
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "common/PxBase.h"
#include "geometry/PxGeometry.h"
#include "geometry/PxGeometryHelpers.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxBoxGeometry;
class PxSphereGeometry;
class PxCapsuleGeometry;
class PxPlaneGeometry;
class PxConvexMeshGeometry;
class PxTriangleMeshGeometry;
class PxHeightFieldGeometry;
class PxRigidActor;
struct PxFilterData;
struct PxRaycastHit;
struct PxSweepHit;
/**
\brief Flags which affect the behavior of PxShapes.
@see PxShape PxShape.setFlag()
*/
struct PxShapeFlag
{
enum Enum
{
/**
\brief The shape will partake in collision in the physical simulation.
\note It is illegal to raise the eSIMULATION_SHAPE and eTRIGGER_SHAPE flags.
In the event that one of these flags is already raised the sdk will reject any
attempt to raise the other. To raise the eSIMULATION_SHAPE first ensure that
eTRIGGER_SHAPE is already lowered.
\note This flag has no effect if simulation is disabled for the corresponding actor (see #PxActorFlag::eDISABLE_SIMULATION).
@see PxSimulationEventCallback.onContact() PxScene.setSimulationEventCallback() PxShape.setFlag(), PxShape.setFlags()
*/
eSIMULATION_SHAPE = (1<<0),
/**
\brief The shape will partake in scene queries (ray casts, overlap tests, sweeps, ...).
*/
eSCENE_QUERY_SHAPE = (1<<1),
/**
\brief The shape is a trigger which can send reports whenever other shapes enter/leave its volume.
\note Triangle meshes and heightfields can not be triggers. Shape creation will fail in these cases.
\note Shapes marked as triggers do not collide with other objects. If an object should act both
as a trigger shape and a collision shape then create a rigid body with two shapes, one being a
trigger shape and the other a collision shape. It is illegal to raise the eTRIGGER_SHAPE and
eSIMULATION_SHAPE flags on a single PxShape instance. In the event that one of these flags is already
raised the sdk will reject any attempt to raise the other. To raise the eTRIGGER_SHAPE flag first
ensure that eSIMULATION_SHAPE flag is already lowered.
\note Trigger shapes will no longer send notification events for interactions with other trigger shapes.
\note Shapes marked as triggers are allowed to participate in scene queries, provided the eSCENE_QUERY_SHAPE flag is set.
\note This flag has no effect if simulation is disabled for the corresponding actor (see #PxActorFlag::eDISABLE_SIMULATION).
@see PxSimulationEventCallback.onTrigger() PxScene.setSimulationEventCallback() PxShape.setFlag(), PxShape.setFlags()
*/
eTRIGGER_SHAPE = (1<<2),
/**
\brief Enable debug renderer for this shape
@see PxScene.getRenderBuffer() PxRenderBuffer PxVisualizationParameter
*/
eVISUALIZATION = (1<<3)
};
};
/**
\brief collection of set bits defined in PxShapeFlag.
@see PxShapeFlag
*/
typedef PxFlags<PxShapeFlag::Enum,PxU8> PxShapeFlags;
PX_FLAGS_OPERATORS(PxShapeFlag::Enum,PxU8)
/**
\brief Abstract class for collision shapes.
Shapes are shared, reference counted objects.
An instance can be created by calling the createShape() method of the PxRigidActor class, or
the createShape() method of the PxPhysics class.
<h3>Visualizations</h3>
\li PxVisualizationParameter::eCOLLISION_AABBS
\li PxVisualizationParameter::eCOLLISION_SHAPES
\li PxVisualizationParameter::eCOLLISION_AXES
@see PxPhysics.createShape() PxRigidActor.createShape() PxBoxGeometry PxSphereGeometry PxCapsuleGeometry PxPlaneGeometry PxConvexMeshGeometry
PxTriangleMeshGeometry PxHeightFieldGeometry
*/
class PxShape : public PxBase
{
public:
/**
\brief Decrements the reference count of a shape and releases it if the new reference count is zero.
Note that in releases prior to PhysX 3.3 this method did not have reference counting semantics and was used to destroy a shape
created with PxActor::createShape(). In PhysX 3.3 and above, this usage is deprecated, instead, use PxRigidActor::detachShape() to detach
a shape from an actor. If the shape to be detached was created with PxActor::createShape(), the actor holds the only counted reference,
and so when the shape is detached it will also be destroyed.
@see PxRigidActor::createShape() PxPhysics::createShape() PxRigidActor::attachShape() PxRigidActor::detachShape()
*/
virtual void release() = 0;
/**
\brief Returns the reference count of the shape.
At creation, the reference count of the shape is 1. Every actor referencing this shape increments the
count by 1. When the reference count reaches 0, and only then, the shape gets destroyed automatically.
\return the current reference count.
*/
virtual PxU32 getReferenceCount() const = 0;
/**
\brief Acquires a counted reference to a shape.
This method increases the reference count of the shape by 1. Decrement the reference count by calling release()
*/
virtual void acquireReference() = 0;
/**
\brief Get the geometry type of the shape.
\return Type of shape geometry.
@see PxGeometryType
*/
virtual PxGeometryType::Enum getGeometryType() const = 0;
/**
\brief Adjust the geometry of the shape.
\note The type of the passed in geometry must match the geometry type of the shape.
\note It is not allowed to change the geometry type of a shape.
\note This function does not guarantee correct/continuous behavior when objects are resting on top of old or new geometry.
\param[in] geometry New geometry of the shape.
@see PxGeometry PxGeometryType getGeometryType()
*/
virtual void setGeometry(const PxGeometry& geometry) = 0;
/**
\brief Retrieve the geometry from the shape in a PxGeometryHolder wrapper class.
\return a PxGeometryHolder object containing the geometry;
@see PxGeometry PxGeometryType getGeometryType() setGeometry()
*/
virtual PxGeometryHolder getGeometry() const = 0;
/**
\brief Fetch the geometry of the shape.
\note If the type of geometry to extract does not match the geometry type of the shape
then the method will return false and the passed in geometry descriptor is not modified.
\param[in] geometry The descriptor to save the shape's geometry data to.
\return True on success else false
@see PxGeometry PxGeometryType getGeometryType()
*/
virtual bool getBoxGeometry(PxBoxGeometry& geometry) const = 0;
/**
\brief Fetch the geometry of the shape.
\note If the type of geometry to extract does not match the geometry type of the shape
then the method will return false and the passed in geometry descriptor is not modified.
\param[in] geometry The descriptor to save the shape's geometry data to.
\return True on success else false
@see PxGeometry PxGeometryType getGeometryType()
*/
virtual bool getSphereGeometry(PxSphereGeometry& geometry) const = 0;
/**
\brief Fetch the geometry of the shape.
\note If the type of geometry to extract does not match the geometry type of the shape
then the method will return false and the passed in geometry descriptor is not modified.
\param[in] geometry The descriptor to save the shape's geometry data to.
\return True on success else false
@see PxGeometry PxGeometryType getGeometryType()
*/
virtual bool getCapsuleGeometry(PxCapsuleGeometry& geometry) const = 0;
/**
\brief Fetch the geometry of the shape.
\note If the type of geometry to extract does not match the geometry type of the shape
then the method will return false and the passed in geometry descriptor is not modified.
\param[in] geometry The descriptor to save the shape's geometry data to.
\return True on success else false
@see PxGeometry PxGeometryType getGeometryType()
*/
virtual bool getPlaneGeometry(PxPlaneGeometry& geometry) const = 0;
/**
\brief Fetch the geometry of the shape.
\note If the type of geometry to extract does not match the geometry type of the shape
then the method will return false and the passed in geometry descriptor is not modified.
\param[in] geometry The descriptor to save the shape's geometry data to.
\return True on success else false
@see PxGeometry PxGeometryType getGeometryType()
*/
virtual bool getConvexMeshGeometry(PxConvexMeshGeometry& geometry) const = 0;
/**
\brief Fetch the geometry of the shape.
\note If the type of geometry to extract does not match the geometry type of the shape
then the method will return false and the passed in geometry descriptor is not modified.
\param[in] geometry The descriptor to save the shape's geometry data to.
\return True on success else false
@see PxGeometry PxGeometryType getGeometryType()
*/
virtual bool getTriangleMeshGeometry(PxTriangleMeshGeometry& geometry) const = 0;
/**
\brief Fetch the geometry of the shape.
\note If the type of geometry to extract does not match the geometry type of the shape
then the method will return false and the passed in geometry descriptor is not modified.
\param[in] geometry The descriptor to save the shape's geometry data to.
\return True on success else false
@see PxGeometry PxGeometryType getGeometryType()
*/
virtual bool getHeightFieldGeometry(PxHeightFieldGeometry& geometry) const = 0;
/**
\brief Retrieves the actor which this shape is associated with.
\return The actor this shape is associated with, if it is an exclusive shape, else NULL
@see PxRigidStatic, PxRigidDynamic, PxArticulationLink
*/
virtual PxRigidActor* getActor() const = 0;
/************************************************************************************************/
/** @name Pose Manipulation
*/
//@{
/**
\brief Sets the pose of the shape in actor space, i.e. relative to the actors to which they are attached.
This transformation is identity by default.
The local pose is an attribute of the shape, and so will apply to all actors to which the shape is attached.
<b>Sleeping:</b> Does <b>NOT</b> wake the associated actor up automatically.
<i>Note:</i> Does not automatically update the inertia properties of the owning actor (if applicable); use the
PhysX extensions method #PxRigidBodyExt::updateMassAndInertia() to do this.
<b>Default:</b> the identity transform
\param[in] pose The new transform from the actor frame to the shape frame. <b>Range:</b> rigid body transform
@see getLocalPose()
*/
virtual void setLocalPose(const PxTransform& pose) = 0;
/**
\brief Retrieves the pose of the shape in actor space, i.e. relative to the actor they are owned by.
This transformation is identity by default.
\return Pose of shape relative to the actor's frame.
@see setLocalPose()
*/
virtual PxTransform getLocalPose() const = 0;
//@}
/************************************************************************************************/
/** @name Collision Filtering
*/
//@{
/**
\brief Sets the user definable collision filter data.
<b>Sleeping:</b> Does wake up the actor if the filter data change causes a formerly suppressed
collision pair to be enabled.
<b>Default:</b> (0,0,0,0)
@see getSimulationFilterData()
*/
virtual void setSimulationFilterData(const PxFilterData& data) = 0;
/**
\brief Retrieves the shape's collision filter data.
@see setSimulationFilterData()
*/
virtual PxFilterData getSimulationFilterData() const = 0;
/**
\brief Sets the user definable query filter data.
<b>Default:</b> (0,0,0,0)
@see getQueryFilterData()
*/
virtual void setQueryFilterData(const PxFilterData& data) = 0;
/**
\brief Retrieves the shape's Query filter data.
@see setQueryFilterData()
*/
virtual PxFilterData getQueryFilterData() const = 0;
//@}
/************************************************************************************************/
/**
\brief Assigns material(s) to the shape.
<b>Sleeping:</b> Does <b>NOT</b> wake the associated actor up automatically.
\param[in] materials List of material pointers to assign to the shape. See #PxMaterial
\param[in] materialCount The number of materials provided.
@see PxPhysics.createMaterial() getMaterials()
*/
virtual void setMaterials(PxMaterial*const* materials, PxU16 materialCount) = 0;
/**
\brief Returns the number of materials assigned to the shape.
You can use #getMaterials() to retrieve the material pointers.
\return Number of materials associated with this shape.
@see PxMaterial getMaterials()
*/
virtual PxU16 getNbMaterials() const = 0;
/**
\brief Retrieve all the material pointers associated with the shape.
You can retrieve the number of material pointers by calling #getNbMaterials()
Note: Removing materials with #PxMaterial::release() will invalidate the pointer of the released material.
\param[out] userBuffer The buffer to store the material pointers.
\param[in] bufferSize Size of provided user buffer.
\param[in] startIndex Index of first material pointer to be retrieved
\return Number of material pointers written to the buffer.
@see PxMaterial getNbMaterials() PxMaterial::release()
*/
virtual PxU32 getMaterials(PxMaterial** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
/**
\brief Retrieve material from given triangle index.
The input index is the internal triangle index as used inside the SDK. This is the index
returned to users by various SDK functions such as raycasts.
This function is only useful for triangle meshes or heightfields, which have per-triangle
materials. For other shapes the function returns the single material associated with the
shape, regardless of the index.
\param[in] faceIndex The internal triangle index whose material you want to retrieve.
\return Material from input triangle
\note If faceIndex value of 0xFFFFffff is passed as an input for mesh and heightfield shapes, this function will issue a warning and return NULL.
\note Scene queries set the value of PxQueryHit::faceIndex to 0xFFFFffff whenever it is undefined or does not apply.
@see PxMaterial getNbMaterials() PxMaterial::release()
*/
virtual PxMaterial* getMaterialFromInternalFaceIndex(PxU32 faceIndex) const = 0;
/**
\brief Sets the contact offset.
Shapes whose distance is less than the sum of their contactOffset values will generate contacts. The contact offset must be positive and
greater than the rest offset. Having a contactOffset greater than than the restOffset allows the collision detection system to
predictively enforce the contact constraint even when the objects are slightly separated. This prevents jitter that would occur
if the constraint were enforced only when shapes were within the rest distance.
<b>Default:</b> 0.02f * PxTolerancesScale::length
<b>Sleeping:</b> Does <b>NOT</b> wake the associated actor up automatically.
\param[in] contactOffset <b>Range:</b> [maximum(0,restOffset), PX_MAX_F32)
@see getContactOffset PxTolerancesScale setRestOffset
*/
virtual void setContactOffset(PxReal contactOffset) = 0;
/**
\brief Retrieves the contact offset.
\return The contact offset of the shape.
@see setContactOffset()
*/
virtual PxReal getContactOffset() const = 0;
/**
\brief Sets the rest offset.
Two shapes will come to rest at a distance equal to the sum of their restOffset values. If the restOffset is 0, they should converge to touching
exactly. Having a restOffset greater than zero is useful to have objects slide smoothly, so that they do not get hung up on irregularities of
each others' surfaces.
<b>Default:</b> 0.0f
<b>Sleeping:</b> Does <b>NOT</b> wake the associated actor up automatically.
\param[in] restOffset <b>Range:</b> (-PX_MAX_F32, contactOffset)
@see getRestOffset setContactOffset
*/
virtual void setRestOffset(PxReal restOffset) = 0;
/**
\brief Retrieves the rest offset.
\return The rest offset of the shape.
@see setRestOffset()
*/
virtual PxReal getRestOffset() const = 0;
/**
\brief Sets torsional patch radius.
This defines the radius of the contact patch used to apply torsional friction. If the radius is 0, no torsional friction
will be applied. If the radius is > 0, some torsional friction will be applied. This is proportional to the penetration depth
so, if the shapes are separated or penetration is zero, no torsional friction will be applied. It is used to approximate
rotational friction introduced by the compression of contacting surfaces.
\param[in] radius <b>Range:</b> (0, PX_MAX_F32)
*/
virtual void setTorsionalPatchRadius(PxReal radius) = 0;
/**
\brief Gets torsional patch radius.
This defines the radius of the contact patch used to apply torsional friction. If the radius is 0, no torsional friction
will be applied. If the radius is > 0, some torsional friction will be applied. This is proportional to the penetration depth
so, if the shapes are separated or penetration is zero, no torsional friction will be applied. It is used to approximate
rotational friction introduced by the compression of contacting surfaces.
\return The torsional patch radius of the shape.
*/
virtual PxReal getTorsionalPatchRadius() const = 0;
/**
\brief Sets minimum torsional patch radius.
This defines the minimum radius of the contact patch used to apply torsional friction. If the radius is 0, the amount of torsional friction
that will be applied will be entirely dependent on the value of torsionalPatchRadius.
If the radius is > 0, some torsional friction will be applied regardless of the value of torsionalPatchRadius or the amount of penetration.
\param[in] radius <b>Range:</b> (0, PX_MAX_F32)
*/
virtual void setMinTorsionalPatchRadius(PxReal radius) = 0;
/**
\brief Gets minimum torsional patch radius.
This defines the minimum radius of the contact patch used to apply torsional friction. If the radius is 0, the amount of torsional friction
that will be applied will be entirely dependent on the value of torsionalPatchRadius.
If the radius is > 0, some torsional friction will be applied regardless of the value of torsionalPatchRadius or the amount of penetration.
\return The minimum torsional patch radius of the shape.
*/
virtual PxReal getMinTorsionalPatchRadius() const = 0;
/************************************************************************************************/
/**
\brief Sets shape flags
<b>Sleeping:</b> Does <b>NOT</b> wake the associated actor up automatically.
\param[in] flag The shape flag to enable/disable. See #PxShapeFlag.
\param[in] value True to set the flag. False to clear the flag specified in flag.
<b>Default:</b> PxShapeFlag::eVISUALIZATION | PxShapeFlag::eSIMULATION_SHAPE | PxShapeFlag::eSCENE_QUERY_SHAPE
@see PxShapeFlag getFlags()
*/
virtual void setFlag(PxShapeFlag::Enum flag, bool value) = 0;
/**
\brief Sets shape flags
@see PxShapeFlag getFlags()
*/
virtual void setFlags(PxShapeFlags inFlags) = 0;
/**
\brief Retrieves shape flags.
\return The values of the shape flags.
@see PxShapeFlag setFlag()
*/
virtual PxShapeFlags getFlags() const = 0;
/**
\brief Returns true if the shape is exclusive to an actor.
@see PxPhysics::createShape()
*/
virtual bool isExclusive() 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.
<b>Default:</b> NULL
\param[in] name The 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 The name associated with the shape.
@see setName()
*/
virtual const char* getName() const = 0;
virtual const char* getConcreteTypeName() const { return "PxShape"; }
/************************************************************************************************/
void* userData; //!< user can assign this to whatever, usually to create a 1:1 relationship with a user object.
protected:
PX_INLINE PxShape(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
PX_INLINE PxShape(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags), userData(NULL) {}
virtual ~PxShape() {}
virtual bool isKindOf(const char* name) const { return !::strcmp("PxShape", name) || PxBase::isKindOf(name); }
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,915 @@
//
// 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-2018 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_SIMULATION_EVENT_CALLBACK
#define PX_SIMULATION_EVENT_CALLBACK
/** \addtogroup physics
@{
*/
#include "foundation/PxVec3.h"
#include "foundation/PxTransform.h"
#include "foundation/PxMemory.h"
#include "PxPhysXConfig.h"
#include "PxFiltering.h"
#include "PxContact.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxShape;
class PxActor;
class PxRigidActor;
class PxRigidBody;
class PxConstraint;
/**
\brief Extra data item types for contact pairs.
@see PxContactPairExtraDataItem.type
*/
struct PxContactPairExtraDataType
{
enum Enum
{
ePRE_SOLVER_VELOCITY, //!< see #PxContactPairVelocity
ePOST_SOLVER_VELOCITY, //!< see #PxContactPairVelocity
eCONTACT_EVENT_POSE, //!< see #PxContactPairPose
eCONTACT_PAIR_INDEX //!< see #PxContactPairIndex
};
};
/**
\brief Base class for items in the extra data stream of contact pairs
@see PxContactPairHeader.extraDataStream
*/
struct PxContactPairExtraDataItem
{
public:
PX_FORCE_INLINE PxContactPairExtraDataItem() {}
/**
\brief The type of the extra data stream item
*/
PxU8 type;
};
/**
\brief Velocities of the contact pair rigid bodies
This struct is shared by multiple types of extra data items. The #type field allows to distinguish between them:
\li PxContactPairExtraDataType::ePRE_SOLVER_VELOCITY: see #PxPairFlag::ePRE_SOLVER_VELOCITY
\li PxContactPairExtraDataType::ePOST_SOLVER_VELOCITY: see #PxPairFlag::ePOST_SOLVER_VELOCITY
\note For static rigid bodies, the velocities will be set to zero.
@see PxContactPairHeader.extraDataStream
*/
struct PxContactPairVelocity : public PxContactPairExtraDataItem
{
public:
PX_FORCE_INLINE PxContactPairVelocity() {}
/**
\brief The linear velocity of the rigid bodies
*/
PxVec3 linearVelocity[2];
/**
\brief The angular velocity of the rigid bodies
*/
PxVec3 angularVelocity[2];
};
/**
\brief World space actor poses of the contact pair rigid bodies
@see PxContactPairHeader.extraDataStream PxPairFlag::eCONTACT_EVENT_POSE
*/
struct PxContactPairPose : public PxContactPairExtraDataItem
{
public:
PX_FORCE_INLINE PxContactPairPose() {}
/**
\brief The world space pose of the rigid bodies
*/
PxTransform globalPose[2];
};
/**
\brief Marker for the beginning of a new item set in the extra data stream.
If CCD with multiple passes is enabled, then a fast moving object might bounce on and off the same
object multiple times. Also, different shapes of the same actor might gain and lose contact with an other
object over multiple passes. This marker allows to seperate the extra data items for each collision case, as well as
distinguish the shape pair reports of different CCD passes.
Example:
Let us assume that an actor a0 with shapes s0_0 and s0_1 hits another actor a1 with shape s1.
First s0_0 will hit s1, then a0 will slightly rotate and s0_1 will hit s1 while s0_0 will lose contact with s1.
Furthermore, let us say that contact event pose information is requested as extra data.
The extra data stream will look like this:
PxContactPairIndexA | PxContactPairPoseA | PxContactPairIndexB | PxContactPairPoseB
The corresponding array of PxContactPair events (see #PxSimulationEventCallback.onContact()) will look like this:
PxContactPair(touch_found: s0_0, s1) | PxContactPair(touch_lost: s0_0, s1) | PxContactPair(touch_found: s0_1, s1)
The #index of PxContactPairIndexA will point to the first entry in the PxContactPair array, for PxContactPairIndexB,
#index will point to the third entry.
@see PxContactPairHeader.extraDataStream
*/
struct PxContactPairIndex : public PxContactPairExtraDataItem
{
public:
PX_FORCE_INLINE PxContactPairIndex() {}
/**
\brief The next item set in the extra data stream refers to the contact pairs starting at #index in the reported PxContactPair array.
*/
PxU16 index;
};
/**
\brief A class to iterate over a contact pair extra data stream.
@see PxContactPairHeader.extraDataStream
*/
struct PxContactPairExtraDataIterator
{
/**
\brief Constructor
\param[in] stream Pointer to the start of the stream.
\param[in] size Size of the stream in bytes.
*/
PX_FORCE_INLINE PxContactPairExtraDataIterator(const PxU8* stream, PxU32 size)
: currPtr(stream), endPtr(stream + size), contactPairIndex(0)
{
clearDataPtrs();
}
/**
\brief Advances the iterator to next set of extra data items.
The contact pair extra data stream contains sets of items as requested by the corresponding #PxPairFlag flags
#PxPairFlag::ePRE_SOLVER_VELOCITY, #PxPairFlag::ePOST_SOLVER_VELOCITY, #PxPairFlag::eCONTACT_EVENT_POSE. A set can contain one
item of each plus the PxContactPairIndex item. This method parses the stream and points the iterator
member variables to the corresponding items of the current set, if they are available. If CCD is not enabled,
you should only get one set of items. If CCD with multiple passes is enabled, you might get more than one item
set.
\note Even though contact pair extra data is requested per shape pair, you will not get an item set per shape pair
but one per actor pair. If, for example, an actor has two shapes and both collide with another actor, then
there will only be one item set (since it applies to both shape pairs).
\return True if there was another set of extra data items in the stream, else false.
@see PxContactPairVelocity PxContactPairPose PxContactPairIndex
*/
PX_INLINE bool nextItemSet()
{
clearDataPtrs();
bool foundEntry = false;
bool endOfItemSet = false;
while ((currPtr < endPtr) && (!endOfItemSet))
{
const PxContactPairExtraDataItem* edItem = reinterpret_cast<const PxContactPairExtraDataItem*>(currPtr);
PxU8 type = edItem->type;
switch(type)
{
case PxContactPairExtraDataType::ePRE_SOLVER_VELOCITY:
{
PX_ASSERT(!preSolverVelocity);
preSolverVelocity = static_cast<const PxContactPairVelocity*>(edItem);
currPtr += sizeof(PxContactPairVelocity);
foundEntry = true;
}
break;
case PxContactPairExtraDataType::ePOST_SOLVER_VELOCITY:
{
postSolverVelocity = static_cast<const PxContactPairVelocity*>(edItem);
currPtr += sizeof(PxContactPairVelocity);
foundEntry = true;
}
break;
case PxContactPairExtraDataType::eCONTACT_EVENT_POSE:
{
eventPose = static_cast<const PxContactPairPose*>(edItem);
currPtr += sizeof(PxContactPairPose);
foundEntry = true;
}
break;
case PxContactPairExtraDataType::eCONTACT_PAIR_INDEX:
{
if (!foundEntry)
{
contactPairIndex = static_cast<const PxContactPairIndex*>(edItem)->index;
currPtr += sizeof(PxContactPairIndex);
foundEntry = true;
}
else
endOfItemSet = true;
}
break;
default:
return foundEntry;
}
}
return foundEntry;
}
private:
/**
\brief Internal helper
*/
PX_FORCE_INLINE void clearDataPtrs()
{
preSolverVelocity = NULL;
postSolverVelocity = NULL;
eventPose = NULL;
}
public:
/**
\brief Current pointer in the stream.
*/
const PxU8* currPtr;
/**
\brief Pointer to the end of the stream.
*/
const PxU8* endPtr;
/**
\brief Pointer to the current pre solver velocity item in the stream. NULL if there is none.
@see PxContactPairVelocity
*/
const PxContactPairVelocity* preSolverVelocity;
/**
\brief Pointer to the current post solver velocity item in the stream. NULL if there is none.
@see PxContactPairVelocity
*/
const PxContactPairVelocity* postSolverVelocity;
/**
\brief Pointer to the current contact event pose item in the stream. NULL if there is none.
@see PxContactPairPose
*/
const PxContactPairPose* eventPose;
/**
\brief The contact pair index of the current item set in the stream.
@see PxContactPairIndex
*/
PxU32 contactPairIndex;
};
/**
\brief Collection of flags providing information on contact report pairs.
@see PxContactPairHeader
*/
struct PxContactPairHeaderFlag
{
enum Enum
{
eREMOVED_ACTOR_0 = (1<<0), //!< The actor with index 0 has been removed from the scene.
eREMOVED_ACTOR_1 = (1<<1) //!< The actor with index 1 has been removed from the scene.
};
};
/**
\brief Bitfield that contains a set of raised flags defined in PxContactPairHeaderFlag.
@see PxContactPairHeaderFlag
*/
typedef PxFlags<PxContactPairHeaderFlag::Enum, PxU16> PxContactPairHeaderFlags;
PX_FLAGS_OPERATORS(PxContactPairHeaderFlag::Enum, PxU16)
/**
\brief An Instance of this class is passed to PxSimulationEventCallback.onContact().
@see PxSimulationEventCallback.onContact()
*/
struct PxContactPairHeader
{
public:
PX_INLINE PxContactPairHeader() {}
/**
\brief The two actors of the notification shape pairs.
\note The actor pointers might reference deleted actors. This will be the case if PxPairFlag::eNOTIFY_TOUCH_LOST
or PxPairFlag::eNOTIFY_THRESHOLD_FORCE_LOST events were requested for the pair and one of the involved actors
gets deleted or removed from the scene. Check the #flags member to see whether that is the case.
Do not dereference a pointer to a deleted actor. The pointer to a deleted actor is only provided
such that user data structures which might depend on the pointer value can be updated.
@see PxActor
*/
PxRigidActor* actors[2];
/**
\brief Stream containing extra data as requested in the PxPairFlag flags of the simulation filter.
This pointer is only valid if any kind of extra data information has been requested for the contact report pair (see #PxPairFlag::ePOST_SOLVER_VELOCITY etc.),
else it will be NULL.
@see PxPairFlag
*/
const PxU8* extraDataStream;
/**
\brief Size of the extra data stream [bytes]
*/
PxU16 extraDataStreamSize;
/**
\brief Additional information on the contact report pair.
@see PxContactPairHeaderFlag
*/
PxContactPairHeaderFlags flags;
/**
\brief pointer to the contact pairs
*/
const struct PxContactPair* pairs;
/**
\brief number of contact pairs
*/
PxU32 nbPairs;
};
/**
\brief Collection of flags providing information on contact report pairs.
@see PxContactPair
*/
struct PxContactPairFlag
{
enum Enum
{
/**
\brief The shape with index 0 has been removed from the actor/scene.
*/
eREMOVED_SHAPE_0 = (1<<0),
/**
\brief The shape with index 1 has been removed from the actor/scene.
*/
eREMOVED_SHAPE_1 = (1<<1),
/**
\brief First actor pair contact.
The provided shape pair marks the first contact between the two actors, no other shape pair has been touching prior to the current simulation frame.
\note: This info is only available if #PxPairFlag::eNOTIFY_TOUCH_FOUND has been declared for the pair.
*/
eACTOR_PAIR_HAS_FIRST_TOUCH = (1<<2),
/**
\brief All contact between the actor pair was lost.
All contact between the two actors has been lost, no shape pairs remain touching after the current simulation frame.
*/
eACTOR_PAIR_LOST_TOUCH = (1<<3),
/**
\brief Internal flag, used by #PxContactPair.extractContacts()
The applied contact impulses are provided for every contact point.
This is the case if #PxPairFlag::eSOLVE_CONTACT has been set for the pair.
*/
eINTERNAL_HAS_IMPULSES = (1<<4),
/**
\brief Internal flag, used by #PxContactPair.extractContacts()
The provided contact point information is flipped with regards to the shapes of the contact pair. This mainly concerns the order of the internal triangle indices.
*/
eINTERNAL_CONTACTS_ARE_FLIPPED = (1<<5)
};
};
/**
\brief Bitfield that contains a set of raised flags defined in PxContactPairFlag.
@see PxContactPairFlag
*/
typedef PxFlags<PxContactPairFlag::Enum, PxU16> PxContactPairFlags;
PX_FLAGS_OPERATORS(PxContactPairFlag::Enum, PxU16)
/**
\brief A contact point as used by contact notification
*/
struct PxContactPairPoint
{
/**
\brief The position of the contact point between the shapes, in world space.
*/
PxVec3 position;
/**
\brief The separation of the shapes at the contact point. A negative separation denotes a penetration.
*/
PxReal separation;
/**
\brief The normal of the contacting surfaces at the contact point. The normal direction points from the second shape to the first shape.
*/
PxVec3 normal;
/**
\brief The surface index of shape 0 at the contact point. This is used to identify the surface material.
*/
PxU32 internalFaceIndex0;
/**
\brief The impulse applied at the contact point, in world space. Divide by the simulation time step to get a force value.
*/
PxVec3 impulse;
/**
\brief The surface index of shape 1 at the contact point. This is used to identify the surface material.
*/
PxU32 internalFaceIndex1;
};
/**
\brief Contact report pair information.
Instances of this class are passed to PxSimulationEventCallback.onContact(). If contact reports have been requested for a pair of shapes (see #PxPairFlag),
then the corresponding contact information will be provided through this structure.
@see PxSimulationEventCallback.onContact()
*/
struct PxContactPair
{
public:
PX_INLINE PxContactPair() {}
/**
\brief The two shapes that make up the pair.
\note The shape pointers might reference deleted shapes. This will be the case if #PxPairFlag::eNOTIFY_TOUCH_LOST
or #PxPairFlag::eNOTIFY_THRESHOLD_FORCE_LOST events were requested for the pair and one of the involved shapes
gets deleted. Check the #flags member to see whether that is the case. Do not dereference a pointer to a
deleted shape. The pointer to a deleted shape is only provided such that user data structures which might
depend on the pointer value can be updated.
@see PxShape
*/
PxShape* shapes[2];
/**
\brief Pointer to first patch header in contact stream containing contact patch data
This pointer is only valid if contact point information has been requested for the contact report pair (see #PxPairFlag::eNOTIFY_CONTACT_POINTS).
Use #extractContacts() as a reference for the data layout of the stream.
*/
const PxU8* contactPatches;
/**
\brief Pointer to first contact point in contact stream containing contact data
This pointer is only valid if contact point information has been requested for the contact report pair (see #PxPairFlag::eNOTIFY_CONTACT_POINTS).
Use #extractContacts() as a reference for the data layout of the stream.
*/
const PxU8* contactPoints;
/**
\brief Buffer containing applied impulse data.
This pointer is only valid if contact point information has been requested for the contact report pair (see #PxPairFlag::eNOTIFY_CONTACT_POINTS).
Use #extractContacts() as a reference for the data layout of the stream.
*/
const PxReal* contactImpulses;
/**
\brief Size of the contact stream [bytes] including force buffer
*/
PxU32 requiredBufferSize;
/**
\brief Number of contact points stored in the contact stream
*/
PxU8 contactCount;
/**
\brief Number of contact patches stored in the contact stream
*/
PxU8 patchCount;
/**
\brief Size of the contact stream [bytes] not including force buffer
*/
PxU16 contactStreamSize;
/**
\brief Additional information on the contact report pair.
@see PxContactPairFlag
*/
PxContactPairFlags flags;
/**
\brief Flags raised due to the contact.
The events field is a combination of:
<ul>
<li>PxPairFlag::eNOTIFY_TOUCH_FOUND,</li>
<li>PxPairFlag::eNOTIFY_TOUCH_PERSISTS,</li>
<li>PxPairFlag::eNOTIFY_TOUCH_LOST,</li>
<li>PxPairFlag::eNOTIFY_TOUCH_CCD,</li>
<li>PxPairFlag::eNOTIFY_THRESHOLD_FORCE_FOUND,</li>
<li>PxPairFlag::eNOTIFY_THRESHOLD_FORCE_PERSISTS,</li>
<li>PxPairFlag::eNOTIFY_THRESHOLD_FORCE_LOST</li>
</ul>
See the documentation of #PxPairFlag for an explanation of each.
\note eNOTIFY_TOUCH_CCD can get raised even if the pair did not request this event. However, in such a case it will only get
raised in combination with one of the other flags to point out that the other event occured during a CCD pass.
@see PxPairFlag
*/
PxPairFlags events;
PxU32 internalData[2]; // For internal use only
/**
\brief Extracts the contact points from the stream and stores them in a convenient format.
\param[out] userBuffer Array of PxContactPairPoint structures to extract the contact points to. The number of contacts for a pair is defined by #contactCount
\param[in] bufferSize Number of PxContactPairPoint structures the provided buffer can store.
\return Number of contact points written to the buffer.
@see PxContactPairPoint
*/
PX_INLINE PxU32 extractContacts(PxContactPairPoint* userBuffer, PxU32 bufferSize) const;
/**
\brief Helper method to clone the contact pair and copy the contact data stream into a user buffer.
The contact data stream is only accessible during the contact report callback. This helper function provides copy functionality
to buffer the contact stream information such that it can get accessed at a later stage.
\param[out] newPair The contact pair info will get copied to this instance. The contact data stream pointer of the copy will be redirected to the provided user buffer. Use NULL to skip the contact pair copy operation.
\param[out] bufferMemory Memory block to store the contact data stream to. At most #requiredBufferSize bytes will get written to the buffer.
*/
PX_INLINE void bufferContacts(PxContactPair* newPair, PxU8* bufferMemory) const;
PX_INLINE const PxU32* getInternalFaceIndices() const;
};
PX_INLINE PxU32 PxContactPair::extractContacts(PxContactPairPoint* userBuffer, PxU32 bufferSize) const
{
PxU32 nbContacts = 0;
if(contactCount && bufferSize)
{
PxContactStreamIterator iter(contactPatches, contactPoints, getInternalFaceIndices(), patchCount, contactCount);
const PxReal* impulses = contactImpulses;
const PxU32 flippedContacts = (flags & PxContactPairFlag::eINTERNAL_CONTACTS_ARE_FLIPPED);
const PxU32 hasImpulses = (flags & PxContactPairFlag::eINTERNAL_HAS_IMPULSES);
while(iter.hasNextPatch())
{
iter.nextPatch();
while(iter.hasNextContact())
{
iter.nextContact();
PxContactPairPoint& dst = userBuffer[nbContacts];
dst.position = iter.getContactPoint();
dst.separation = iter.getSeparation();
dst.normal = iter.getContactNormal();
if(!flippedContacts)
{
dst.internalFaceIndex0 = iter.getFaceIndex0();
dst.internalFaceIndex1 = iter.getFaceIndex1();
}
else
{
dst.internalFaceIndex0 = iter.getFaceIndex1();
dst.internalFaceIndex1 = iter.getFaceIndex0();
}
if(hasImpulses)
{
const PxReal impulse = impulses[nbContacts];
dst.impulse = dst.normal * impulse;
}
else
dst.impulse = PxVec3(0.0f);
++nbContacts;
if(nbContacts == bufferSize)
return nbContacts;
}
}
}
return nbContacts;
}
PX_INLINE void PxContactPair::bufferContacts(PxContactPair* newPair, PxU8* bufferMemory) const
{
PxU8* patches = bufferMemory;
PxU8* contacts = NULL;
if(patches)
{
contacts = bufferMemory + patchCount * sizeof(PxContactPatch);
PxMemCopy(patches, contactPatches, sizeof(PxContactPatch)*patchCount);
PxMemCopy(contacts, contactPoints, contactStreamSize - (sizeof(PxContactPatch)*patchCount));
}
if(contactImpulses)
{
PxMemCopy(bufferMemory + ((contactStreamSize + 15) & (~15)), contactImpulses, sizeof(PxReal) * contactCount);
}
if (newPair)
{
*newPair = *this;
newPair->contactPatches = patches;
newPair->contactPoints = contacts;
}
}
PX_INLINE const PxU32* PxContactPair::getInternalFaceIndices() const
{
return reinterpret_cast<const PxU32*>(contactImpulses + contactCount);
}
/**
\brief Collection of flags providing information on trigger report pairs.
@see PxTriggerPair
*/
struct PxTriggerPairFlag
{
enum Enum
{
eREMOVED_SHAPE_TRIGGER = (1<<0), //!< The trigger shape has been removed from the actor/scene.
eREMOVED_SHAPE_OTHER = (1<<1), //!< The shape causing the trigger event has been removed from the actor/scene.
eNEXT_FREE = (1<<2) //!< For internal use only.
};
};
/**
\brief Bitfield that contains a set of raised flags defined in PxTriggerPairFlag.
@see PxTriggerPairFlag
*/
typedef PxFlags<PxTriggerPairFlag::Enum, PxU8> PxTriggerPairFlags;
PX_FLAGS_OPERATORS(PxTriggerPairFlag::Enum, PxU8)
/**
\brief Descriptor for a trigger pair.
An array of these structs gets passed to the PxSimulationEventCallback::onTrigger() report.
\note The shape pointers might reference deleted shapes. This will be the case if #PxPairFlag::eNOTIFY_TOUCH_LOST
events were requested for the pair and one of the involved shapes gets deleted. Check the #flags member to see
whether that is the case. Do not dereference a pointer to a deleted shape. The pointer to a deleted shape is
only provided such that user data structures which might depend on the pointer value can be updated.
@see PxSimulationEventCallback.onTrigger()
*/
struct PxTriggerPair
{
PX_INLINE PxTriggerPair() {}
PxShape* triggerShape; //!< The shape that has been marked as a trigger.
PxRigidActor* triggerActor; //!< The actor to which triggerShape is attached
PxShape* otherShape; //!< The shape causing the trigger event. \deprecated (see #PxSimulationEventCallback::onTrigger()) If collision between trigger shapes is enabled, then this member might point to a trigger shape as well.
PxRigidActor* otherActor; //!< The actor to which otherShape is attached
PxPairFlag::Enum status; //!< Type of trigger event (eNOTIFY_TOUCH_FOUND or eNOTIFY_TOUCH_LOST). eNOTIFY_TOUCH_PERSISTS events are not supported.
PxTriggerPairFlags flags; //!< Additional information on the pair (see #PxTriggerPairFlag)
};
/**
\brief Descriptor for a broken constraint.
An array of these structs gets passed to the PxSimulationEventCallback::onConstraintBreak() report.
@see PxConstraint PxSimulationEventCallback.onConstraintBreak()
*/
struct PxConstraintInfo
{
PX_INLINE PxConstraintInfo() {}
PX_INLINE PxConstraintInfo(PxConstraint* c, void* extRef, PxU32 t) : constraint(c), externalReference(extRef), type(t) {}
PxConstraint* constraint; //!< The broken constraint.
void* externalReference; //!< The external object which owns the constraint (see #PxConstraintConnector::getExternalReference())
PxU32 type; //!< Unique type ID of the external object. Allows to cast the provided external reference to the appropriate type
};
/**
\brief An interface class that the user can implement in order to receive simulation events.
With the exception of onAdvance(), the events get sent during the call to either #PxScene::fetchResults() or
#PxScene::flushSimulation() with sendPendingReports=true. onAdvance() gets called while the simulation
is running (that is between PxScene::simulate(), onAdvance() and PxScene::fetchResults()).
\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> With the exception of onAdvance(), it is not necessary to make these callbacks thread safe as
they will only be called in the context of the user thread.
@see PxScene.setSimulationEventCallback() PxScene.getSimulationEventCallback()
*/
class PxSimulationEventCallback
{
public:
/**
\brief This is called when a breakable constraint breaks.
\note The user should not release the constraint shader inside this call!
\note No event will get reported if the constraint breaks but gets deleted while the time step is still being simulated.
\param[in] constraints - The constraints which have been broken.
\param[in] count - The number of constraints
@see PxConstraint PxConstraintDesc.linearBreakForce PxConstraintDesc.angularBreakForce
*/
virtual void onConstraintBreak(PxConstraintInfo* constraints, PxU32 count) = 0;
/**
\brief This is called with the actors which have just been woken up.
\note Only supported by rigid bodies yet.
\note Only called on actors for which the PxActorFlag eSEND_SLEEP_NOTIFIES has been set.
\note Only the latest sleep state transition happening between fetchResults() of the previous frame and fetchResults() of the current frame
will get reported. For example, let us assume actor A is awake, then A->putToSleep() gets called, then later A->wakeUp() gets called.
At the next simulate/fetchResults() step only an onWake() event will get triggered because that was the last transition.
\note If an actor gets newly added to a scene with properties such that it is awake and the sleep state does not get changed by
the user or simulation, then an onWake() event will get sent at the next simulate/fetchResults() step.
\param[in] actors - The actors which just woke up.
\param[in] count - The number of actors
@see PxScene.setSimulationEventCallback() PxSceneDesc.simulationEventCallback PxActorFlag PxActor.setActorFlag()
*/
virtual void onWake(PxActor** actors, PxU32 count) = 0;
/**
\brief This is called with the actors which have just been put to sleep.
\note Only supported by rigid bodies yet.
\note Only called on actors for which the PxActorFlag eSEND_SLEEP_NOTIFIES has been set.
\note Only the latest sleep state transition happening between fetchResults() of the previous frame and fetchResults() of the current frame
will get reported. For example, let us assume actor A is asleep, then A->wakeUp() gets called, then later A->putToSleep() gets called.
At the next simulate/fetchResults() step only an onSleep() event will get triggered because that was the last transition (assuming the simulation
does not wake the actor up).
\note If an actor gets newly added to a scene with properties such that it is asleep and the sleep state does not get changed by
the user or simulation, then an onSleep() event will get sent at the next simulate/fetchResults() step.
\param[in] actors - The actors which have just been put to sleep.
\param[in] count - The number of actors
@see PxScene.setSimulationEventCallback() PxSceneDesc.simulationEventCallback PxActorFlag PxActor.setActorFlag()
*/
virtual void onSleep(PxActor** actors, PxU32 count) = 0;
/**
\brief This is called when certain contact events occur.
The method will be called for a pair of actors if one of the colliding shape pairs requested contact notification.
You request which events are reported using the filter shader/callback mechanism (see #PxSimulationFilterShader,
#PxSimulationFilterCallback, #PxPairFlag).
Do not keep references to the passed objects, as they will be
invalid after this function returns.
\param[in] pairHeader Information on the two actors whose shapes triggered a contact report.
\param[in] pairs The contact pairs of two actors for which contact reports have been requested. See #PxContactPair.
\param[in] nbPairs The number of provided contact pairs.
@see PxScene.setSimulationEventCallback() PxSceneDesc.simulationEventCallback PxContactPair PxPairFlag PxSimulationFilterShader PxSimulationFilterCallback
*/
virtual void onContact(const PxContactPairHeader& pairHeader, const PxContactPair* pairs, PxU32 nbPairs) = 0;
/**
\brief This is called with the current trigger pair events.
Shapes which have been marked as triggers using PxShapeFlag::eTRIGGER_SHAPE will send events
according to the pair flag specification in the filter shader (see #PxPairFlag, #PxSimulationFilterShader).
\note Trigger shapes will no longer send notification events for interactions with other trigger shapes.
\param[in] pairs - The trigger pair events.
\param[in] count - The number of trigger pair events.
@see PxScene.setSimulationEventCallback() PxSceneDesc.simulationEventCallback PxPairFlag PxSimulationFilterShader PxShapeFlag PxShape.setFlag()
*/
virtual void onTrigger(PxTriggerPair* pairs, PxU32 count) = 0;
/**
\brief Provides early access to the new pose of moving rigid bodies.
When this call occurs, rigid bodies having the #PxRigidBodyFlag::eENABLE_POSE_INTEGRATION_PREVIEW
flag set, were moved by the simulation and their new poses can be accessed through the provided buffers.
\note The provided buffers are valid and can be read until the next call to #PxScene::simulate() or #PxScene::collide().
\note Buffered user changes to the rigid body pose will not yet be reflected in the provided data. More important,
the provided data might contain bodies that have been deleted while the simulation was running. It is the user's
responsibility to detect and avoid dereferencing such bodies.
\note This callback gets triggered while the simulation is running. If the provided rigid body references are used to
read properties of the object, then the callback has to guarantee no other thread is writing to the same body at the same
time.
\note The code in this callback should be lightweight as it can block the simulation, that is, the
#PxScene::fetchResults() call.
\param[in] bodyBuffer The rigid bodies that moved and requested early pose reporting.
\param[in] poseBuffer The integrated rigid body poses of the bodies listed in bodyBuffer.
\param[in] count The number of entries in the provided buffers.
@see PxScene.setSimulationEventCallback() PxSceneDesc.simulationEventCallback PxRigidBodyFlag::eENABLE_POSE_INTEGRATION_PREVIEW
*/
virtual void onAdvance(const PxRigidBody*const* bodyBuffer, const PxTransform* poseBuffer, const PxU32 count) = 0;
virtual ~PxSimulationEventCallback() {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,330 @@
//
// 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-2018 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_SIMULATION_STATISTICS
#define PX_SIMULATION_STATISTICS
/** \addtogroup physics
@{
*/
#include "PxPhysXConfig.h"
#include "foundation/PxAssert.h"
#include "geometry/PxGeometry.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Class used to retrieve statistics for a simulation step.
@see PxScene::getSimulationStatistics()
*/
class PxSimulationStatistics
{
public:
/**
\brief Different types of rigid body collision pair statistics.
@see getRbPairStats
*/
enum RbPairStatsType
{
/**
\brief Shape pairs processed as discrete contact pairs for the current simulation step.
*/
eDISCRETE_CONTACT_PAIRS,
/**
\brief Shape pairs processed as swept integration pairs for the current simulation step.
\note Counts the pairs for which special CCD (continuous collision detection) work was actually done and NOT the number of pairs which were configured for CCD.
Furthermore, there can be multiple CCD passes and all processed pairs of all passes are summed up, hence the number can be larger than the amount of pairs which have been configured for CCD.
@see PxPairFlag::eDETECT_CCD_CONTACT,
*/
eCCD_PAIRS,
/**
\brief Shape pairs processed with user contact modification enabled for the current simulation step.
@see PxContactModifyCallback
*/
eMODIFIED_CONTACT_PAIRS,
/**
\brief Trigger shape pairs processed for the current simulation step.
@see PxShapeFlag::eTRIGGER_SHAPE
*/
eTRIGGER_PAIRS
};
//objects:
/**
\brief Number of active PxConstraint objects (joints etc.) for the current simulation step.
*/
PxU32 nbActiveConstraints;
/**
\brief Number of active dynamic bodies for the current simulation step.
\note Does not include active kinematic bodies
*/
PxU32 nbActiveDynamicBodies;
/**
\brief Number of active kinematic bodies for the current simulation step.
\note Kinematic deactivation occurs at the end of the frame after the last call to PxRigidDynamic::setKinematicTarget() was called so kinematics that are
deactivated in a given frame will be included by this counter.
*/
PxU32 nbActiveKinematicBodies;
/**
\brief Number of static bodies for the current simulation step.
*/
PxU32 nbStaticBodies;
/**
\brief Number of dynamic bodies for the current simulation step.
\note Includes inactive and kinematic bodies, and articulation links
*/
PxU32 nbDynamicBodies;
/**
\brief Number of shapes of each geometry type.
*/
PxU32 nbShapes[PxGeometryType::eGEOMETRY_COUNT];
/**
\brief Number of aggregates in the scene.
*/
PxU32 nbAggregates;
/**
\brief Number of articulations in the scene.
*/
PxU32 nbArticulations;
//solver:
/**
\brief The number of 1D axis constraints(joints+contact) present in the current simulation step.
*/
PxU32 nbAxisSolverConstraints;
/**
\brief The size (in bytes) of the compressed contact stream in the current simulation step
*/
PxU32 compressedContactSize;
/**
\brief The total required size (in bytes) of the contact constraints in the current simulation step
*/
PxU32 requiredContactConstraintMemory;
/**
\brief The peak amount of memory (in bytes) that was allocated for constraints (this includes joints) in the current simulation step
*/
PxU32 peakConstraintMemory;
//broadphase:
/**
\brief Get number of broadphase volumes added for the current simulation step.
\return Number of broadphase volumes added.
*/
PX_FORCE_INLINE PxU32 getNbBroadPhaseAdds() const
{
return nbBroadPhaseAdds;
}
/**
\brief Get number of broadphase volumes removed for the current simulation step.
\return Number of broadphase volumes removed.
*/
PX_FORCE_INLINE PxU32 getNbBroadPhaseRemoves() const
{
return nbBroadPhaseRemoves;
}
//collisions:
/**
\brief Get number of shape collision pairs of a certain type processed for the current simulation step.
There is an entry for each geometry pair type.
\note entry[i][j] = entry[j][i], hence, if you want the sum of all pair
types, you need to discard the symmetric entries
\param[in] pairType The type of pair for which to get information
\param[in] g0 The geometry type of one pair object
\param[in] g1 The geometry type of the other pair object
\return Number of processed pairs of the specified geometry types.
*/
PxU32 getRbPairStats(RbPairStatsType pairType, PxGeometryType::Enum g0, PxGeometryType::Enum g1) const
{
PX_ASSERT_WITH_MESSAGE( (pairType >= eDISCRETE_CONTACT_PAIRS) &&
(pairType <= eTRIGGER_PAIRS),
"Invalid pairType in PxSimulationStatistics::getRbPairStats");
if (g0 >= PxGeometryType::eGEOMETRY_COUNT || g1 >= PxGeometryType::eGEOMETRY_COUNT)
{
PX_ASSERT(false);
return 0;
}
PxU32 nbPairs = 0;
switch(pairType)
{
case eDISCRETE_CONTACT_PAIRS:
nbPairs = nbDiscreteContactPairs[g0][g1];
break;
case eCCD_PAIRS:
nbPairs = nbCCDPairs[g0][g1];
break;
case eMODIFIED_CONTACT_PAIRS:
nbPairs = nbModifiedContactPairs[g0][g1];
break;
case eTRIGGER_PAIRS:
nbPairs = nbTriggerPairs[g0][g1];
break;
}
return nbPairs;
}
/**
\brief Total number of (non CCD) pairs reaching narrow phase
*/
PxU32 nbDiscreteContactPairsTotal;
/**
\brief Total number of (non CCD) pairs for which contacts are successfully cached (<=nbDiscreteContactPairsTotal)
\note This includes pairs for which no contacts are generated, it still counts as a cache hit.
*/
PxU32 nbDiscreteContactPairsWithCacheHits;
/**
\brief Total number of (non CCD) pairs for which at least 1 contact was generated (<=nbDiscreteContactPairsTotal)
*/
PxU32 nbDiscreteContactPairsWithContacts;
/**
\brief Number of new pairs found by BP this frame
*/
PxU32 nbNewPairs;
/**
\brief Number of lost pairs from BP this frame
*/
PxU32 nbLostPairs;
/**
\brief Number of new touches found by NP this frame
*/
PxU32 nbNewTouches;
/**
\brief Number of lost touches from NP this frame
*/
PxU32 nbLostTouches;
/**
\brief Number of partitions used by the solver this frame
*/
PxU32 nbPartitions;
PxSimulationStatistics() :
nbActiveConstraints (0),
nbActiveDynamicBodies (0),
nbActiveKinematicBodies (0),
nbStaticBodies (0),
nbDynamicBodies (0),
nbAggregates (0),
nbArticulations (0),
nbAxisSolverConstraints (0),
compressedContactSize (0),
requiredContactConstraintMemory (0),
peakConstraintMemory (0),
nbDiscreteContactPairsTotal (0),
nbDiscreteContactPairsWithCacheHits (0),
nbDiscreteContactPairsWithContacts (0),
nbNewPairs (0),
nbLostPairs (0),
nbNewTouches (0),
nbLostTouches (0),
nbPartitions (0)
{
nbBroadPhaseAdds = 0;
nbBroadPhaseRemoves = 0;
for(PxU32 i=0; i < PxGeometryType::eGEOMETRY_COUNT; i++)
{
for(PxU32 j=0; j < PxGeometryType::eGEOMETRY_COUNT; j++)
{
nbDiscreteContactPairs[i][j] = 0;
nbModifiedContactPairs[i][j] = 0;
nbCCDPairs[i][j] = 0;
nbTriggerPairs[i][j] = 0;
}
}
for(PxU32 i=0; i < PxGeometryType::eGEOMETRY_COUNT; i++)
{
nbShapes[i] = 0;
}
}
//
// We advise to not access these members directly. Use the provided accessor methods instead.
//
//broadphase:
PxU32 nbBroadPhaseAdds;
PxU32 nbBroadPhaseRemoves;
//collisions:
PxU32 nbDiscreteContactPairs[PxGeometryType::eGEOMETRY_COUNT][PxGeometryType::eGEOMETRY_COUNT];
PxU32 nbCCDPairs[PxGeometryType::eGEOMETRY_COUNT][PxGeometryType::eGEOMETRY_COUNT];
PxU32 nbModifiedContactPairs[PxGeometryType::eGEOMETRY_COUNT][PxGeometryType::eGEOMETRY_COUNT];
PxU32 nbTriggerPairs[PxGeometryType::eGEOMETRY_COUNT][PxGeometryType::eGEOMETRY_COUNT];
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,254 @@
//
// 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-2018 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_DEBUG_VISUALIZATION_PARAMETER
#define PX_PHYSICS_NX_DEBUG_VISUALIZATION_PARAMETER
#include "foundation/PxPreprocessor.h"
/** \addtogroup physics
@{
*/
#if !PX_DOXYGEN
namespace physx
{
#endif
/*
NOTE: Parameters should NOT be conditionally compiled out. Even if a particular feature is not available.
Otherwise the parameter values get shifted about and the numeric values change per platform. This causes problems
when trying to serialize parameters.
New parameters should also be added to the end of the list for this reason. Also make sure to update
eNUM_VALUES, which should be one higher than the maximum value in the enum.
*/
/**
\brief Debug visualization parameters.
#PxVisualizationParameter::eSCALE is the master switch for enabling visualization, please read the corresponding documentation
for further details.
@see PxScene.setVisualizationParameter() PxScene.getVisualizationParameter() PxScene.getRenderBuffer()
*/
struct PxVisualizationParameter
{
enum Enum
{
/* RigidBody-related parameters */
/**
\brief This overall visualization scale gets multiplied with the individual scales. Setting to zero ignores all visualizations. Default is 0.
The below settings permit the debug visualization of various simulation properties.
The setting is either zero, in which case the property is not drawn. Otherwise it is a scaling factor
that determines the size of the visualization widgets.
Only objects for which visualization is turned on using setFlag(eVISUALIZATION) are visualized (see #PxActorFlag::eVISUALIZATION, #PxShapeFlag::eVISUALIZATION, ...).
Contacts are visualized if they involve a body which is being visualized.
Default is 0.
Notes:
- to see any visualization, you have to set PxVisualizationParameter::eSCALE to nonzero first.
- the scale factor has been introduced because it's difficult (if not impossible) to come up with a
good scale for 3D vectors. Normals are normalized and their length is always 1. But it doesn't mean
we should render a line of length 1. Depending on your objects/scene, this might be completely invisible
or extremely huge. That's why the scale factor is here, to let you tune the length until it's ok in
your scene.
- however, things like collision shapes aren't ambiguous. They are clearly defined for example by the
triangles & polygons themselves, and there's no point in scaling that. So the visualization widgets
are only scaled when it makes sense.
<b>Range:</b> [0, PX_MAX_F32)<br>
<b>Default:</b> 0
*/
eSCALE,
/**
\brief Visualize the world axes.
*/
eWORLD_AXES,
/* Body visualizations */
/**
\brief Visualize a bodies axes.
@see PxActor.globalPose PxActor
*/
eBODY_AXES,
/**
\brief Visualize a body's mass axes.
This visualization is also useful for visualizing the sleep state of bodies. Sleeping bodies are drawn in
black, while awake bodies are drawn in white. If the body is sleeping and part of a sleeping group, it is
drawn in red.
@see PxBodyDesc.massLocalPose PxActor
*/
eBODY_MASS_AXES,
/**
\brief Visualize the bodies linear velocity.
@see PxBodyDesc.linearVelocity PxActor
*/
eBODY_LIN_VELOCITY,
/**
\brief Visualize the bodies angular velocity.
@see PxBodyDesc.angularVelocity PxActor
*/
eBODY_ANG_VELOCITY,
/* Contact visualisations */
/**
\brief Visualize contact points. Will enable contact information.
*/
eCONTACT_POINT,
/**
\brief Visualize contact normals. Will enable contact information.
*/
eCONTACT_NORMAL,
/**
\brief Visualize contact errors. Will enable contact information.
*/
eCONTACT_ERROR,
/**
\brief Visualize Contact forces. Will enable contact information.
*/
eCONTACT_FORCE,
/**
\brief Visualize actor axes.
@see PxRigidStatic PxRigidDynamic PxArticulationLink
*/
eACTOR_AXES,
/**
\brief Visualize bounds (AABBs in world space)
*/
eCOLLISION_AABBS,
/**
\brief Shape visualization
@see PxShape
*/
eCOLLISION_SHAPES,
/**
\brief Shape axis visualization
@see PxShape
*/
eCOLLISION_AXES,
/**
\brief Compound visualization (compound AABBs in world space)
*/
eCOLLISION_COMPOUNDS,
/**
\brief Mesh & convex face normals
@see PxTriangleMesh PxConvexMesh
*/
eCOLLISION_FNORMALS,
/**
\brief Active edges for meshes
@see PxTriangleMesh
*/
eCOLLISION_EDGES,
/**
\brief Static pruning structures
*/
eCOLLISION_STATIC,
/**
\brief Dynamic pruning structures
*/
eCOLLISION_DYNAMIC,
/**
\brief Visualizes pairwise state.
*/
eDEPRECATED_COLLISION_PAIRS,
/**
\brief Joint local axes
*/
eJOINT_LOCAL_FRAMES,
/**
\brief Joint limits
*/
eJOINT_LIMITS,
/**
\brief Visualize culling box
*/
eCULL_BOX,
/**
\brief MBP regions
*/
eMBP_REGIONS,
/**
\brief This is not a parameter, it just records the current number of parameters (as maximum(PxVisualizationParameter)+1) for use in loops.
*/
eNUM_VALUES,
eFORCE_DWORD = 0x7fffffff
};
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,230 @@
//
// 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-2018 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_CCT_BOX_CONTROLLER
#define PX_PHYSICS_CCT_BOX_CONTROLLER
/** \addtogroup character
@{
*/
#include "characterkinematic/PxCharacter.h"
#include "characterkinematic/PxController.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Descriptor for a box character controller.
@see PxBoxController PxControllerDesc
*/
class PxBoxControllerDesc : public PxControllerDesc
{
public:
/**
\brief constructor sets to default.
*/
PX_INLINE PxBoxControllerDesc();
PX_INLINE virtual ~PxBoxControllerDesc() {}
/**
\brief copy constructor.
*/
PX_INLINE PxBoxControllerDesc(const PxBoxControllerDesc&);
/**
\brief assignment operator.
*/
PX_INLINE PxBoxControllerDesc& operator=(const PxBoxControllerDesc&);
/**
\brief (re)sets the structure to the default.
*/
PX_INLINE virtual void setToDefault();
/**
\brief returns true if the current settings are valid
\return True if the descriptor is valid.
*/
PX_INLINE virtual bool isValid() const;
/**
\brief Half height
<b>Default:</b> 1.0
*/
PxF32 halfHeight; // Half-height in the "up" direction
/**
\brief Half side extent
<b>Default:</b> 0.5
*/
PxF32 halfSideExtent; // Half-extent in the "side" direction
/**
\brief Half forward extent
<b>Default:</b> 0.5
*/
PxF32 halfForwardExtent; // Half-extent in the "forward" direction
protected:
PX_INLINE void copy(const PxBoxControllerDesc&);
};
PX_INLINE PxBoxControllerDesc::PxBoxControllerDesc() :
PxControllerDesc (PxControllerShapeType::eBOX),
halfHeight (1.0f),
halfSideExtent (0.5f),
halfForwardExtent (0.5f)
{
}
PX_INLINE PxBoxControllerDesc::PxBoxControllerDesc(const PxBoxControllerDesc& other) : PxControllerDesc(other)
{
copy(other);
}
PX_INLINE PxBoxControllerDesc& PxBoxControllerDesc::operator=(const PxBoxControllerDesc& other)
{
PxControllerDesc::operator=(other);
copy(other);
return *this;
}
PX_INLINE void PxBoxControllerDesc::copy(const PxBoxControllerDesc& other)
{
halfHeight = other.halfHeight;
halfSideExtent = other.halfSideExtent;
halfForwardExtent = other.halfForwardExtent;
}
PX_INLINE void PxBoxControllerDesc::setToDefault()
{
*this = PxBoxControllerDesc();
}
PX_INLINE bool PxBoxControllerDesc::isValid() const
{
if(!PxControllerDesc::isValid()) return false;
if(halfHeight<=0.0f) return false;
if(halfSideExtent<=0.0f) return false;
if(halfForwardExtent<=0.0f) return false;
if(stepOffset>2.0f*halfHeight) return false; // Prevents obvious mistakes
return true;
}
/**
\brief Box character controller.
@see PxBoxControllerDesc PxController
*/
class PxBoxController : public PxController
{
public:
/**
\brief Gets controller's half height.
\return The half height of the controller.
@see PxBoxControllerDesc.halfHeight setHalfHeight()
*/
virtual PxF32 getHalfHeight() const = 0;
/**
\brief Gets controller's half side extent.
\return The half side extent of the controller.
@see PxBoxControllerDesc.halfSideExtent setHalfSideExtent()
*/
virtual PxF32 getHalfSideExtent() const = 0;
/**
\brief Gets controller's half forward extent.
\return The half forward extent of the controller.
@see PxBoxControllerDesc.halfForwardExtent setHalfForwardExtent()
*/
virtual PxF32 getHalfForwardExtent() const = 0;
/**
\brief Sets controller's half height.
\warning this doesn't check for collisions.
\param[in] halfHeight The new half height for the controller.
\return Currently always true.
@see PxBoxControllerDesc.halfHeight getHalfHeight()
*/
virtual bool setHalfHeight(PxF32 halfHeight) = 0;
/**
\brief Sets controller's half side extent.
\warning this doesn't check for collisions.
\param[in] halfSideExtent The new half side extent for the controller.
\return Currently always true.
@see PxBoxControllerDesc.halfSideExtent getHalfSideExtent()
*/
virtual bool setHalfSideExtent(PxF32 halfSideExtent) = 0;
/**
\brief Sets controller's half forward extent.
\warning this doesn't check for collisions.
\param[in] halfForwardExtent The new half forward extent for the controller.
\return Currently always true.
@see PxBoxControllerDesc.halfForwardExtent getHalfForwardExtent()
*/
virtual bool setHalfForwardExtent(PxF32 halfForwardExtent) = 0;
protected:
PX_INLINE PxBoxController() {}
virtual ~PxBoxController() {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,251 @@
//
// 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-2018 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_CCT_CAPSULE_CONTROLLER
#define PX_PHYSICS_CCT_CAPSULE_CONTROLLER
/** \addtogroup character
@{
*/
#include "characterkinematic/PxCharacter.h"
#include "characterkinematic/PxController.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
struct PxCapsuleClimbingMode
{
enum Enum
{
eEASY, //!< Standard mode, let the capsule climb over surfaces according to impact normal
eCONSTRAINED, //!< Constrained mode, try to limit climbing according to the step offset
eLAST
};
};
/**
\brief A descriptor for a capsule character controller.
@see PxCapsuleController PxControllerDesc
*/
class PxCapsuleControllerDesc : public PxControllerDesc
{
public:
/**
\brief constructor sets to default.
*/
PX_INLINE PxCapsuleControllerDesc ();
PX_INLINE virtual ~PxCapsuleControllerDesc () {}
/**
\brief copy constructor.
*/
PX_INLINE PxCapsuleControllerDesc(const PxCapsuleControllerDesc&);
/**
\brief assignment operator.
*/
PX_INLINE PxCapsuleControllerDesc& operator=(const PxCapsuleControllerDesc&);
/**
\brief (re)sets the structure to the default.
*/
PX_INLINE virtual void setToDefault();
/**
\brief returns true if the current settings are valid
\return True if the descriptor is valid.
*/
PX_INLINE virtual bool isValid() const;
/**
\brief The radius of the capsule
<b>Default:</b> 0.0
@see PxCapsuleController
*/
PxF32 radius;
/**
\brief The height of the controller
<b>Default:</b> 0.0
@see PxCapsuleController
*/
PxF32 height;
/**
\brief The climbing mode
<b>Default:</b> PxCapsuleClimbingMode::eEASY
@see PxCapsuleController
*/
PxCapsuleClimbingMode::Enum climbingMode;
protected:
PX_INLINE void copy(const PxCapsuleControllerDesc&);
};
PX_INLINE PxCapsuleControllerDesc::PxCapsuleControllerDesc () : PxControllerDesc(PxControllerShapeType::eCAPSULE)
{
radius = height = 0.0f;
climbingMode = PxCapsuleClimbingMode::eEASY;
}
PX_INLINE PxCapsuleControllerDesc::PxCapsuleControllerDesc(const PxCapsuleControllerDesc& other) : PxControllerDesc(other)
{
copy(other);
}
PX_INLINE PxCapsuleControllerDesc& PxCapsuleControllerDesc::operator=(const PxCapsuleControllerDesc& other)
{
PxControllerDesc::operator=(other);
copy(other);
return *this;
}
PX_INLINE void PxCapsuleControllerDesc::copy(const PxCapsuleControllerDesc& other)
{
radius = other.radius;
height = other.height;
climbingMode = other.climbingMode;
}
PX_INLINE void PxCapsuleControllerDesc::setToDefault()
{
*this = PxCapsuleControllerDesc();
}
PX_INLINE bool PxCapsuleControllerDesc::isValid() const
{
if(!PxControllerDesc::isValid()) return false;
if(radius<=0.0f) return false;
if(height<=0.0f) return false;
if(stepOffset>height+radius*2.0f) return false; // Prevents obvious mistakes
return true;
}
/**
\brief A capsule character controller.
The capsule is defined as a position, a vertical height, and a radius.
The height is the distance between the two sphere centers at the end of the capsule.
In other words:
p = pos (returned by controller)<br>
h = height<br>
r = radius<br>
p = center of capsule<br>
top sphere center = p.y + h*0.5<br>
bottom sphere center = p.y - h*0.5<br>
top capsule point = p.y + h*0.5 + r<br>
bottom capsule point = p.y - h*0.5 - r<br>
*/
class PxCapsuleController : public PxController
{
public:
/**
\brief Gets controller's radius.
\return The radius of the controller.
@see PxCapsuleControllerDesc.radius setRadius()
*/
virtual PxF32 getRadius() const = 0;
/**
\brief Sets controller's radius.
\warning this doesn't check for collisions.
\param[in] radius The new radius for the controller.
\return Currently always true.
@see PxCapsuleControllerDesc.radius getRadius()
*/
virtual bool setRadius(PxF32 radius) = 0;
/**
\brief Gets controller's height.
\return The height of the capsule controller.
@see PxCapsuleControllerDesc.height setHeight()
*/
virtual PxF32 getHeight() const = 0;
/**
\brief Resets controller's height.
\warning this doesn't check for collisions.
\param[in] height The new height for the controller.
\return Currently always true.
@see PxCapsuleControllerDesc.height getHeight()
*/
virtual bool setHeight(PxF32 height) = 0;
/**
\brief Gets controller's climbing mode.
\return The capsule controller's climbing mode.
@see PxCapsuleControllerDesc.climbingMode setClimbingMode()
*/
virtual PxCapsuleClimbingMode::Enum getClimbingMode() const = 0;
/**
\brief Sets controller's climbing mode.
\param[in] mode The capsule controller's climbing mode.
@see PxCapsuleControllerDesc.climbingMode getClimbingMode()
*/
virtual bool setClimbingMode(PxCapsuleClimbingMode::Enum mode) = 0;
protected:
PX_INLINE PxCapsuleController() {}
virtual ~PxCapsuleController() {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,57 @@
//
// 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-2018 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_CHARACTER_H
#define PX_CHARACTER_H
/** \addtogroup character
@{
*/
#include "foundation/Px.h"
// define API function declaration
#if defined PX_PHYSX_STATIC_LIB || defined PX_PHYSX_CHARACTER_STATIC_LIB
#define PX_PHYSX_CHARACTER_API
#else
#if PX_WINDOWS
#if defined PX_PHYSX_CHARACTER_EXPORTS
#define PX_PHYSX_CHARACTER_API __declspec(dllexport)
#else
#define PX_PHYSX_CHARACTER_API __declspec(dllimport)
#endif
#elif PX_UNIX_FAMILY
#define PX_PHYSX_CHARACTER_API PX_UNIX_EXPORT
#else
#define PX_PHYSX_CHARACTER_API
#endif
#endif
/** @} */
#endif

View File

@ -0,0 +1,911 @@
//
// 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-2018 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_CCT_CONTROLLER
#define PX_PHYSICS_CCT_CONTROLLER
/** \addtogroup character
@{
*/
#include "characterkinematic/PxCharacter.h"
#include "characterkinematic/PxExtended.h"
#include "characterkinematic/PxControllerObstacles.h"
#include "PxQueryFiltering.h"
#include "foundation/PxErrorCallback.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief The type of controller, eg box, sphere or capsule.
*/
struct PxControllerShapeType
{
enum Enum
{
/**
\brief A box controller.
@see PxBoxController PxBoxControllerDesc
*/
eBOX,
/**
\brief A capsule controller
@see PxCapsuleController PxCapsuleControllerDesc
*/
eCAPSULE,
eFORCE_DWORD = 0x7fffffff
};
};
class PxShape;
class PxScene;
class PxController;
class PxRigidDynamic;
class PxMaterial;
struct PxFilterData;
class PxQueryFilterCallback;
class PxControllerBehaviorCallback;
class PxObstacleContext;
class PxObstacle;
/**
\brief specifies how a CCT interacts with non-walkable parts.
This is only used when slopeLimit is non zero. It is currently enabled for static actors only, and not supported for spheres or capsules.
*/
struct PxControllerNonWalkableMode
{
enum Enum
{
ePREVENT_CLIMBING, //!< Stops character from climbing up non-walkable slopes, but doesn't move it otherwise
ePREVENT_CLIMBING_AND_FORCE_SLIDING //!< Stops character from climbing up non-walkable slopes, and forces it to slide down those slopes
};
};
/**
\brief specifies which sides a character is colliding with.
*/
struct PxControllerCollisionFlag
{
enum Enum
{
eCOLLISION_SIDES = (1<<0), //!< Character is colliding to the sides.
eCOLLISION_UP = (1<<1), //!< Character has collision above.
eCOLLISION_DOWN = (1<<2) //!< Character has collision below.
};
};
/**
\brief Bitfield that contains a set of raised flags defined in PxControllerCollisionFlag.
@see PxControllerCollisionFlag
*/
typedef PxFlags<PxControllerCollisionFlag::Enum, PxU8> PxControllerCollisionFlags;
PX_FLAGS_OPERATORS(PxControllerCollisionFlag::Enum, PxU8)
/**
\brief Describes a controller's internal state.
*/
struct PxControllerState
{
PxVec3 deltaXP; //!< delta position vector for the object the CCT is standing/riding on. Not always match the CCT delta when variable timesteps are used.
PxShape* touchedShape; //!< Shape on which the CCT is standing
PxRigidActor* touchedActor; //!< Actor owning 'touchedShape'
ObstacleHandle touchedObstacleHandle; // Obstacle on which the CCT is standing
PxU32 collisionFlags; //!< Last known collision flags (PxControllerCollisionFlag)
bool standOnAnotherCCT; //!< Are we standing on another CCT?
bool standOnObstacle; //!< Are we standing on a user-defined obstacle?
bool isMovingUp; //!< is CCT moving up or not? (i.e. explicit jumping)
};
/**
\brief Describes a controller's internal statistics.
*/
struct PxControllerStats
{
PxU16 nbIterations;
PxU16 nbFullUpdates;
PxU16 nbPartialUpdates;
PxU16 nbTessellation;
};
/**
\brief Describes a generic CCT hit.
*/
struct PxControllerHit
{
PxController* controller; //!< Current controller
PxExtendedVec3 worldPos; //!< Contact position in world space
PxVec3 worldNormal; //!< Contact normal in world space
PxVec3 dir; //!< Motion direction
PxF32 length; //!< Motion length
};
/**
\brief Describes a hit between a CCT and a shape. Passed to onShapeHit()
@see PxUserControllerHitReport.onShapeHit()
*/
struct PxControllerShapeHit : public PxControllerHit
{
PxShape* shape; //!< Touched shape
PxRigidActor* actor; //!< Touched actor
PxU32 triangleIndex; //!< touched triangle index (only for meshes/heightfields)
};
/**
\brief Describes a hit between a CCT and another CCT. Passed to onControllerHit().
@see PxUserControllerHitReport.onControllerHit()
*/
struct PxControllersHit : public PxControllerHit
{
PxController* other; //!< Touched controller
};
/**
\brief Describes a hit between a CCT and a user-defined obstacle. Passed to onObstacleHit().
@see PxUserControllerHitReport.onObstacleHit() PxObstacleContext
*/
struct PxControllerObstacleHit : public PxControllerHit
{
const void* userData;
};
/**
\brief User callback class for character controller events.
\note Character controller hit reports are only generated when move is called.
@see PxControllerDesc.callback
*/
class PxUserControllerHitReport
{
public:
/**
\brief Called when current controller hits a shape.
This is called when the CCT moves and hits a shape. This will not be called when a moving shape hits a non-moving CCT.
\param[in] hit Provides information about the hit.
@see PxControllerShapeHit
*/
virtual void onShapeHit(const PxControllerShapeHit& hit) = 0;
/**
\brief Called when current controller hits another controller.
\param[in] hit Provides information about the hit.
@see PxControllersHit
*/
virtual void onControllerHit(const PxControllersHit& hit) = 0;
/**
\brief Called when current controller hits a user-defined obstacle.
\param[in] hit Provides information about the hit.
@see PxControllerObstacleHit PxObstacleContext
*/
virtual void onObstacleHit(const PxControllerObstacleHit& hit) = 0;
protected:
virtual ~PxUserControllerHitReport(){}
};
/**
\brief Dedicated filtering callback for CCT vs CCT.
This controls collisions between CCTs (one CCT vs anoter CCT).
To make each CCT collide against all other CCTs, just return true - or simply avoid defining a callback.
To make each CCT freely go through all other CCTs, just return false.
Otherwise create a custom filtering logic in this callback.
@see PxControllerFilters
*/
class PxControllerFilterCallback
{
public:
virtual ~PxControllerFilterCallback(){}
/**
\brief Filtering method for CCT-vs-CCT.
\param[in] a First CCT
\param[in] b Second CCT
\return true to keep the pair, false to filter it out
*/
virtual bool filter(const PxController& a, const PxController& b) = 0;
};
/**
\brief Filtering data for "move" call.
This class contains all filtering-related parameters for the PxController::move() call.
Collisions between a CCT and the world are filtered using the mFilterData, mFilterCallback and mFilterFlags
members. These parameters are internally passed to PxScene::overlap() to find objects touched by the CCT.
Please refer to the PxScene::overlap() documentation for details.
Collisions between a CCT and another CCT are filtered using the mCCTFilterCallback member. If this filter
callback is not defined, none of the CCT-vs-CCT collisions are filtered, and each CCT will collide against
all other CCTs.
\note PxQueryFlag::eANY_HIT and PxQueryFlag::eNO_BLOCK are ignored in mFilterFlags.
@see PxController.move() PxControllerFilterCallback
*/
class PxControllerFilters
{
public:
PX_INLINE PxControllerFilters(const PxFilterData* filterData=NULL, PxQueryFilterCallback* cb=NULL, PxControllerFilterCallback* cctFilterCb=NULL) :
mFilterData (filterData),
mFilterCallback (cb),
mFilterFlags (PxQueryFlag::eSTATIC|PxQueryFlag::eDYNAMIC|PxQueryFlag::ePREFILTER),
mCCTFilterCallback (cctFilterCb)
{}
// CCT-vs-shapes:
const PxFilterData* mFilterData; //!< Data for internal PxQueryFilterData structure. Passed to PxScene::overlap() call.
//!< This can be NULL, in which case a default PxFilterData is used.
PxQueryFilterCallback* mFilterCallback; //!< Custom filter logic (can be NULL). Passed to PxScene::overlap() call.
PxQueryFlags mFilterFlags; //!< Flags for internal PxQueryFilterData structure. Passed to PxScene::overlap() call.
// CCT-vs-CCT:
PxControllerFilterCallback* mCCTFilterCallback; //!< CCT-vs-CCT filter callback. If NULL, all CCT-vs-CCT collisions are kept.
};
/**
\brief Descriptor class for a character controller.
@see PxBoxController PxCapsuleController
*/
class PxControllerDesc
{
public:
/**
\brief returns true if the current settings are valid
\return True if the descriptor is valid.
*/
PX_INLINE virtual bool isValid() const;
/**
\brief Returns the character controller type
\return The controllers type.
@see PxControllerType PxCapsuleControllerDesc PxBoxControllerDesc
*/
PX_INLINE PxControllerShapeType::Enum getType() const { return mType; }
/**
\brief The position of the character
\note The character's initial position must be such that it does not overlap the static geometry.
<b>Default:</b> Zero
*/
PxExtendedVec3 position;
/**
\brief Specifies the 'up' direction
In order to provide stepping functionality the SDK must be informed about the up direction.
<b>Default:</b> (0, 1, 0)
*/
PxVec3 upDirection;
/**
\brief The maximum slope which the character can walk up.
In general it is desirable to limit where the character can walk, in particular it is unrealistic
for the character to be able to climb arbitary slopes.
The limit is expressed as the cosine of desired limit angle. A value of 0 disables this feature.
\warning It is currently enabled for static actors only (not for dynamic/kinematic actors), and not supported for spheres or capsules.
<b>Default:</b> 0.707
@see upDirection invisibleWallHeight maxJumpHeight
*/
PxF32 slopeLimit;
/**
\brief Height of invisible walls created around non-walkable triangles
The library can automatically create invisible walls around non-walkable triangles defined
by the 'slopeLimit' parameter. This defines the height of those walls. If it is 0.0, then
no extra triangles are created.
<b>Default:</b> 0.0
@see upDirection slopeLimit maxJumpHeight
*/
PxF32 invisibleWallHeight;
/**
\brief Maximum height a jumping character can reach
This is only used if invisible walls are created ('invisibleWallHeight' is non zero).
When a character jumps, the non-walkable triangles he might fly over are not found
by the collision queries (since the character's bounding volume does not touch them).
Thus those non-walkable triangles do not create invisible walls, and it is possible
for a jumping character to land on a non-walkable triangle, while he wouldn't have
reached that place by just walking.
The 'maxJumpHeight' variable is used to extend the size of the collision volume
downward. This way, all the non-walkable triangles are properly found by the collision
queries and it becomes impossible to 'jump over' invisible walls.
If the character in your game can not jump, it is safe to use 0.0 here. Otherwise it
is best to keep this value as small as possible, since a larger collision volume
means more triangles to process.
<b>Default:</b> 0.0
@see upDirection slopeLimit invisibleWallHeight
*/
PxF32 maxJumpHeight;
/**
\brief The contact offset used by the controller.
Specifies a skin around the object within which contacts will be generated.
Use it to avoid numerical precision issues.
This is dependant on the scale of the users world, but should be a small, positive
non zero value.
<b>Default:</b> 0.1
*/
PxF32 contactOffset;
/**
\brief Defines the maximum height of an obstacle which the character can climb.
A small value will mean that the character gets stuck and cannot walk up stairs etc,
a value which is too large will mean that the character can climb over unrealistically
high obstacles.
<b>Default:</b> 0.5
@see upDirection
*/
PxF32 stepOffset;
/**
\brief Density of underlying kinematic actor
The CCT creates a PhysX's kinematic actor under the hood. This controls its density.
<b>Default:</b> 10.0
*/
PxF32 density;
/**
\brief Scale coefficient for underlying kinematic actor
The CCT creates a PhysX's kinematic actor under the hood. This controls its scale factor.
This should be a number a bit smaller than 1.0.
<b>Default:</b> 0.8
*/
PxF32 scaleCoeff;
/**
\brief Cached volume growth
Amount of space around the controller we cache to improve performance. This is a scale factor
that should be higher than 1.0f but not too big, ideally lower than 2.0f.
<b>Default:</b> 1.5
*/
PxF32 volumeGrowth;
/**
\brief Specifies a user report callback.
This report callback is called when the character collides with shapes and other characters.
Setting this to NULL disables the callback.
<b>Default:</b> NULL
@see PxUserControllerHitReport
*/
PxUserControllerHitReport* reportCallback;
/**
\brief Specifies a user behavior callback.
This behavior callback is called to customize the controller's behavior w.r.t. touched shapes.
Setting this to NULL disables the callback.
<b>Default:</b> NULL
@see PxControllerBehaviorCallback
*/
PxControllerBehaviorCallback* behaviorCallback;
/**
\brief The non-walkable mode controls if a character controller slides or not on a non-walkable part.
This is only used when slopeLimit is non zero.
<b>Default:</b> PxControllerNonWalkableMode::ePREVENT_CLIMBING
@see PxControllerNonWalkableMode
*/
PxControllerNonWalkableMode::Enum nonWalkableMode;
/**
\brief The material for the actor associated with the controller.
The controller internally creates a rigid body actor. This parameter specifies the material of the actor.
<b>Default:</b> NULL
@see PxMaterial
*/
PxMaterial* material;
/**
\brief Use a deletion listener to get informed about released objects and clear internal caches if needed.
If a character controller registers a deletion listener, it will get informed about released objects. That allows the
controller to invalidate cached data that connects to a released object. If a deletion listener is not
registered, PxController::invalidateCache has to be called manually after objects have been released.
@see PxController::invalidateCache
<b>Default:</b> true
*/
bool registerDeletionListener;
/**
\brief User specified data associated with the controller.
<b>Default:</b> NULL
*/
void* userData;
protected:
const PxControllerShapeType::Enum mType; //!< The type of the controller. This gets set by the derived class' ctor, the user should not have to change it.
/**
\brief constructor sets to default.
*/
PX_INLINE PxControllerDesc(PxControllerShapeType::Enum);
PX_INLINE virtual ~PxControllerDesc();
/**
\brief copy constructor.
*/
PX_INLINE PxControllerDesc(const PxControllerDesc&);
/**
\brief assignment operator.
*/
PX_INLINE PxControllerDesc& operator=(const PxControllerDesc&);
PX_INLINE void copy(const PxControllerDesc&);
};
PX_INLINE PxControllerDesc::PxControllerDesc(PxControllerShapeType::Enum t) : mType(t)
{
upDirection = PxVec3(0.0f, 1.0f, 0.0f);
slopeLimit = 0.707f;
contactOffset = 0.1f;
stepOffset = 0.5f;
density = 10.0f;
scaleCoeff = 0.8f;
volumeGrowth = 1.5f;
reportCallback = NULL;
behaviorCallback = NULL;
userData = NULL;
nonWalkableMode = PxControllerNonWalkableMode::ePREVENT_CLIMBING;
position.x = PxExtended(0.0);
position.y = PxExtended(0.0);
position.z = PxExtended(0.0);
material = NULL;
invisibleWallHeight = 0.0f;
maxJumpHeight = 0.0f;
registerDeletionListener = true;
}
PX_INLINE PxControllerDesc::PxControllerDesc(const PxControllerDesc& other) : mType(other.mType)
{
copy(other);
}
PX_INLINE PxControllerDesc& PxControllerDesc::operator=(const PxControllerDesc& other)
{
copy(other);
return *this;
}
PX_INLINE void PxControllerDesc::copy(const PxControllerDesc& other)
{
upDirection = other.upDirection;
slopeLimit = other.slopeLimit;
contactOffset = other.contactOffset;
stepOffset = other.stepOffset;
density = other.density;
scaleCoeff = other.scaleCoeff;
volumeGrowth = other.volumeGrowth;
reportCallback = other.reportCallback;
behaviorCallback = other.behaviorCallback;
userData = other.userData;
nonWalkableMode = other.nonWalkableMode;
position.x = other.position.x;
position.y = other.position.y;
position.z = other.position.z;
material = other.material;
invisibleWallHeight = other.invisibleWallHeight;
maxJumpHeight = other.maxJumpHeight;
registerDeletionListener = other.registerDeletionListener;
}
PX_INLINE PxControllerDesc::~PxControllerDesc()
{
}
PX_INLINE bool PxControllerDesc::isValid() const
{
if( mType!=PxControllerShapeType::eBOX
&& mType!=PxControllerShapeType::eCAPSULE)
return false;
if(scaleCoeff<0.0f) return false;
if(volumeGrowth<1.0f) return false;
if(density<0.0f) return false;
if(slopeLimit<0.0f) return false;
if(stepOffset<0.0f) return false;
if(contactOffset<=0.0f) return false;
if(!material) return false;
return true;
}
/**
\brief Base class for character controllers.
@see PxCapsuleController PxBoxController
*/
class PxController
{
public:
//*********************************************************************
// DEPRECATED FUNCTIONS:
//
// PX_DEPRECATED virtual void setInteraction(PxCCTInteractionMode::Enum flag) = 0;
// PX_DEPRECATED virtual PxCCTInteractionMode::Enum getInteraction() const = 0;
// PX_DEPRECATED virtual void setGroupsBitmask(PxU32 bitmask) = 0;
// PX_DEPRECATED virtual PxU32 getGroupsBitmask() const = 0;
//
// => replaced with:
//
// PxControllerFilters::mCCTFilterCallback. Please define a PxControllerFilterCallback object and emulate the old interaction mode there.
//
//*********************************************************************
/**
\brief Return the type of controller
@see PxControllerType
*/
virtual PxControllerShapeType::Enum getType() const = 0;
/**
\brief Releases the controller.
*/
virtual void release() = 0;
/**
\brief Moves the character using a "collide-and-slide" algorithm.
\param[in] disp Displacement vector
\param[in] minDist The minimum travelled distance to consider. If travelled distance is smaller, the character doesn't move.
This is used to stop the recursive motion algorithm when remaining distance to travel is small.
\param[in] elapsedTime Time elapsed since last call
\param[in] filters User-defined filters for this move
\param[in] obstacles Potential additional obstacles the CCT should collide with.
\return Collision flags, collection of ::PxControllerCollisionFlags
*/
virtual PxControllerCollisionFlags move(const PxVec3& disp, PxF32 minDist, PxF32 elapsedTime, const PxControllerFilters& filters, const PxObstacleContext* obstacles=NULL) = 0;
/**
\brief Sets controller's position.
The position controlled by this function is the center of the collision shape.
\warning This is a 'teleport' function, it doesn't check for collisions.
\warning The character's position must be such that it does not overlap the static geometry.
To move the character under normal conditions use the #move() function.
\param[in] position The new (center) positon for the controller.
\return Currently always returns true.
@see PxControllerDesc.position getPosition() getFootPosition() setFootPosition() move()
*/
virtual bool setPosition(const PxExtendedVec3& position) = 0;
/**
\brief Retrieve the raw position of the controller.
The position retrieved by this function is the center of the collision shape. To retrieve the bottom position of the shape,
a.k.a. the foot position, use the getFootPosition() function.
The position is updated by calls to move(). Calling this method without calling
move() will return the last position or the initial position of the controller.
\return The controller's center position
@see PxControllerDesc.position setPosition() getFootPosition() setFootPosition() move()
*/
virtual const PxExtendedVec3& getPosition() const = 0;
/**
\brief Set controller's foot position.
The position controlled by this function is the bottom of the collision shape, a.k.a. the foot position.
\note The foot position takes the contact offset into account
\warning This is a 'teleport' function, it doesn't check for collisions.
To move the character under normal conditions use the #move() function.
\param[in] position The new (bottom) positon for the controller.
\return Currently always returns true.
@see PxControllerDesc.position setPosition() getPosition() getFootPosition() move()
*/
virtual bool setFootPosition(const PxExtendedVec3& position) = 0;
/**
\brief Retrieve the "foot" position of the controller, i.e. the position of the bottom of the CCT's shape.
\note The foot position takes the contact offset into account
\return The controller's foot position
@see PxControllerDesc.position setPosition() getPosition() setFootPosition() move()
*/
virtual PxExtendedVec3 getFootPosition() const = 0;
/**
\brief Get the rigid body actor associated with this controller (see PhysX documentation).
The behavior upon manually altering this actor is undefined, you should primarily
use it for reading const properties.
\return the actor associated with the controller.
*/
virtual PxRigidDynamic* getActor() const = 0;
/**
\brief The step height.
\param[in] offset The new step offset for the controller.
@see PxControllerDesc.stepOffset
*/
virtual void setStepOffset(const PxF32 offset) =0;
/**
\brief Retrieve the step height.
\return The step offset for the controller.
@see setStepOffset()
*/
virtual PxF32 getStepOffset() const =0;
/**
\brief Sets the non-walkable mode for the CCT.
\param[in] flag The new value of the non-walkable mode.
\see PxControllerNonWalkableMode
*/
virtual void setNonWalkableMode(PxControllerNonWalkableMode::Enum flag) = 0;
/**
\brief Retrieves the non-walkable mode for the CCT.
\return The current non-walkable mode.
\see PxControllerNonWalkableMode
*/
virtual PxControllerNonWalkableMode::Enum getNonWalkableMode() const = 0;
/**
\brief Retrieve the contact offset.
\return The contact offset for the controller.
@see PxControllerDesc.contactOffset
*/
virtual PxF32 getContactOffset() const =0;
/**
\brief Sets the contact offset.
\param[in] offset The contact offset for the controller.
@see PxControllerDesc.contactOffset
*/
virtual void setContactOffset(PxF32 offset) =0;
/**
\brief Retrieve the 'up' direction.
\return The up direction for the controller.
@see PxControllerDesc.upDirection
*/
virtual PxVec3 getUpDirection() const =0;
/**
\brief Sets the 'up' direction.
\param[in] up The up direction for the controller.
@see PxControllerDesc.upDirection
*/
virtual void setUpDirection(const PxVec3& up) =0;
/**
\brief Retrieve the slope limit.
\return The slope limit for the controller.
@see PxControllerDesc.slopeLimit
*/
virtual PxF32 getSlopeLimit() const =0;
/**
\brief Sets the slope limit.
\note This feature can not be enabled at runtime, i.e. if the slope limit is zero when creating the CCT
(which disables the feature) then changing the slope limit at runtime will not have any effect, and the call
will be ignored.
\param[in] slopeLimit The slope limit for the controller.
@see PxControllerDesc.slopeLimit
*/
virtual void setSlopeLimit(PxF32 slopeLimit) =0;
/**
\brief Flushes internal geometry cache.
The character controller uses caching in order to speed up collision testing. The cache is
automatically flushed when a change to static objects is detected in the scene. For example when a
static shape is added, updated, or removed from the scene, the cache is automatically invalidated.
However there may be situations that cannot be automatically detected, and those require manual
invalidation of the cache. Currently the user must call this when the filtering behavior changes (the
PxControllerFilters parameter of the PxController::move call). While the controller in principle
could detect a change in these parameters, it cannot detect a change in the behavior of the filtering
function.
@see PxController.move
*/
virtual void invalidateCache() = 0;
/**
\brief Retrieve the scene associated with the controller.
\return The physics scene
*/
virtual PxScene* getScene() = 0;
/**
\brief Returns the user data associated with this controller.
\return The user pointer associated with the controller.
@see PxControllerDesc.userData
*/
virtual void* getUserData() const = 0;
/**
\brief Sets the user data associated with this controller.
\param[in] userData The user pointer associated with the controller.
@see PxControllerDesc.userData
*/
virtual void setUserData(void* userData) = 0;
/**
\brief Returns information about the controller's internal state.
\param[out] state The controller's internal state
@see PxControllerState
*/
virtual void getState(PxControllerState& state) const = 0;
/**
\brief Returns the controller's internal statistics.
\param[out] stats The controller's internal statistics
@see PxControllerStats
*/
virtual void getStats(PxControllerStats& stats) const = 0;
/**
\brief Resizes the controller.
This function attempts to resize the controller to a given size, while making sure the bottom
position of the controller remains constant. In other words the function modifies both the
height and the (center) position of the controller. This is a helper function that can be used
to implement a 'crouch' functionality for example.
\param[in] height Desired controller's height
*/
virtual void resize(PxReal height) = 0;
protected:
PX_INLINE PxController() {}
virtual ~PxController() {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

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-2018 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_CCT_BEHAVIOR
#define PX_PHYSICS_CCT_BEHAVIOR
/** \addtogroup character
@{
*/
#include "PxFiltering.h"
#include "characterkinematic/PxCharacter.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxShape;
class PxObstacle;
class PxController;
/**
\brief specifies controller behavior
*/
struct PxControllerBehaviorFlag
{
enum Enum
{
eCCT_CAN_RIDE_ON_OBJECT = (1<<0), //!< Controller can ride on touched object (i.e. when this touched object is moving horizontally). \note The CCT vs. CCT case is not supported.
eCCT_SLIDE = (1<<1), //!< Controller should slide on touched object
eCCT_USER_DEFINED_RIDE = (1<<2) //!< Disable all code dealing with controllers riding on objects, let users define it outside of the SDK.
};
};
/**
\brief Bitfield that contains a set of raised flags defined in PxControllerBehaviorFlag.
@see PxControllerBehaviorFlag
*/
typedef PxFlags<PxControllerBehaviorFlag::Enum, PxU8> PxControllerBehaviorFlags;
PX_FLAGS_OPERATORS(PxControllerBehaviorFlag::Enum, PxU8)
/**
\brief User behavior callback.
This behavior callback is called to customize the controller's behavior w.r.t. touched shapes.
*/
class PxControllerBehaviorCallback
{
public:
/**
\brief Retrieve behavior flags for a shape.
When the CCT touches a shape, the CCT's behavior w.r.t. this shape can be customized by users.
This function retrieves the desired PxControllerBehaviorFlag flags capturing the desired behavior.
\note See comments about deprecated functions at the start of this class
\param[in] shape The shape the CCT is currently touching
\param[in] actor The actor owning the shape
\return Desired behavior flags for the given shape
@see PxControllerBehaviorFlag
*/
virtual PxControllerBehaviorFlags getBehaviorFlags(const PxShape& shape, const PxActor& actor) = 0;
/**
\brief Retrieve behavior flags for a controller.
When the CCT touches a controller, the CCT's behavior w.r.t. this controller can be customized by users.
This function retrieves the desired PxControllerBehaviorFlag flags capturing the desired behavior.
\note The flag PxControllerBehaviorFlag::eCCT_CAN_RIDE_ON_OBJECT is not supported.
\note See comments about deprecated functions at the start of this class
\param[in] controller The controller the CCT is currently touching
\return Desired behavior flags for the given controller
@see PxControllerBehaviorFlag
*/
virtual PxControllerBehaviorFlags getBehaviorFlags(const PxController& controller) = 0;
/**
\brief Retrieve behavior flags for an obstacle.
When the CCT touches an obstacle, the CCT's behavior w.r.t. this obstacle can be customized by users.
This function retrieves the desired PxControllerBehaviorFlag flags capturing the desired behavior.
\note See comments about deprecated functions at the start of this class
\param[in] obstacle The obstacle the CCT is currently touching
\return Desired behavior flags for the given obstacle
@see PxControllerBehaviorFlag
*/
virtual PxControllerBehaviorFlags getBehaviorFlags(const PxObstacle& obstacle) = 0;
protected:
virtual ~PxControllerBehaviorCallback(){}
};
#if !PX_DOXYGEN
}
#endif
/** @} */
#endif

View File

@ -0,0 +1,301 @@
//
// 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-2018 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_CCT_MANAGER
#define PX_PHYSICS_CCT_MANAGER
/** \addtogroup character
@{
*/
#include "characterkinematic/PxCharacter.h"
#include "PxPhysXConfig.h"
#include "foundation/PxFlags.h"
#include "foundation/PxErrorCallback.h"
#include "common/PxRenderBuffer.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxPhysics;
class PxScene;
class PxController;
class PxControllerDesc;
class PxObstacleContext;
class PxControllerFilterCallback;
/**
\brief specifies debug-rendering flags
*/
struct PxControllerDebugRenderFlag
{
enum Enum
{
eTEMPORAL_BV = (1<<0), //!< Temporal bounding volume around controllers
eCACHED_BV = (1<<1), //!< Cached bounding volume around controllers
eOBSTACLES = (1<<2), //!< User-defined obstacles
eNONE = 0,
eALL = 0xffffffff
};
};
/**
\brief Bitfield that contains a set of raised flags defined in PxControllerDebugRenderFlag.
@see PxControllerDebugRenderFlag
*/
typedef PxFlags<PxControllerDebugRenderFlag::Enum, PxU32> PxControllerDebugRenderFlags;
PX_FLAGS_OPERATORS(PxControllerDebugRenderFlag::Enum, PxU32)
/**
\brief Manages an array of character controllers.
@see PxController PxBoxController PxCapsuleController
*/
class PX_PHYSX_CHARACTER_API PxControllerManager
{
public:
/**
\brief Releases the controller manager.
\note This will release all associated controllers and obstacle contexts.
\note This function is required to be called to release foundation usage.
*/
virtual void release() = 0;
/**
\brief Returns the scene the manager is adding the controllers to.
\return The associated physics scene.
*/
virtual PxScene& getScene() const = 0;
/**
\brief Returns the number of controllers that are being managed.
\return The number of controllers.
*/
virtual PxU32 getNbControllers() const = 0;
/**
\brief Retrieve one of the controllers in the manager.
\param index the index of the controller to return
\return The controller with the specified index.
*/
virtual PxController* getController(PxU32 index) = 0;
/**
\brief Creates a new character controller.
\param[in] desc The controllers descriptor
\return The new controller
@see PxController PxController.release() PxControllerDesc
*/
virtual PxController* createController(const PxControllerDesc& desc) = 0;
/**
\brief Releases all the controllers that are being managed.
*/
virtual void purgeControllers() = 0;
/**
\brief Retrieves debug data.
\return The render buffer filled with debug-render data
@see PxControllerManager.setDebugRenderingFlags()
*/
virtual PxRenderBuffer& getRenderBuffer() = 0;
/**
\brief Sets debug rendering flags
\param[in] flags The debug rendering flags (combination of PxControllerDebugRenderFlags)
@see PxControllerManager.getRenderBuffer() PxControllerDebugRenderFlags
*/
virtual void setDebugRenderingFlags(PxControllerDebugRenderFlags flags) = 0;
/**
\brief Returns the number of obstacle contexts that are being managed.
\return The number of obstacle contexts.
*/
virtual PxU32 getNbObstacleContexts() const = 0;
/**
\brief Retrieve one of the obstacle contexts in the manager.
\param index The index of the obstacle context to retrieve.
\return The obstacle context with the specified index.
*/
virtual PxObstacleContext* getObstacleContext(PxU32 index) = 0;
/**
\brief Creates an obstacle context.
\return New obstacle context
@see PxObstacleContext
*/
virtual PxObstacleContext* createObstacleContext() = 0;
/**
\brief Computes character-character interactions.
This function is an optional helper to properly resolve interactions between characters, in case they overlap (which can happen for gameplay reasons, etc).
You should call this once per frame, before your PxController::move() calls. The function will not move the characters directly, but it will
compute overlap information for each character that will be used in the next move() call.
You need to provide a proper time value here so that interactions are resolved in a way that do not depend on the framerate.
If you only have one character in the scene, or if you can guarantee your characters will never overlap, then you do not need to call this function.
\note Releasing the manager will automatically release all the associated obstacle contexts.
\param[in] elapsedTime Elapsed time since last call
\param[in] cctFilterCb Filtering callback for CCT-vs-CCT interactions
*/
virtual void computeInteractions(PxF32 elapsedTime, PxControllerFilterCallback* cctFilterCb=NULL) = 0;
/**
\brief Enables or disables runtime tessellation.
Large triangles can create accuracy issues in the sweep code, which in turn can lead to characters not sliding smoothly
against geometries, or even penetrating them. This feature allows one to reduce those issues by tessellating large
triangles at runtime, before performing sweeps against them. The amount of tessellation is controlled by the 'maxEdgeLength' parameter.
Any triangle with at least one edge length greater than the maxEdgeLength will get recursively tessellated, until resulting triangles are small enough.
This features only applies to triangle meshes, convex meshes, heightfields and boxes.
\param[in] flag True/false to enable/disable runtime tessellation.
\param[in] maxEdgeLength Max edge length allowed before tessellation kicks in.
*/
virtual void setTessellation(bool flag, float maxEdgeLength) = 0;
/**
\brief Enables or disables the overlap recovery module.
The overlap recovery module can be used to depenetrate CCTs from static objects when an overlap is detected. This can happen
in three main cases:
- when the CCT is directly spawned or teleported in another object
- when the CCT algorithm fails due to limited FPU accuracy
- when the "up vector" is modified, making the rotated CCT shape overlap surrounding objects
When activated, the CCT module will automatically try to resolve the penetration, and move the CCT to a safe place where it does
not overlap other objects anymore. This only concerns static objects, dynamic objects are ignored by the recovery module.
When the recovery module is not activated, it is possible for the CCTs to go through static objects. By default, the recovery
module is enabled.
The recovery module currently works with all geometries except heightfields.
\param[in] flag True/false to enable/disable overlap recovery module.
*/
virtual void setOverlapRecoveryModule(bool flag) = 0;
/**
\brief Enables or disables the precise sweeps.
Precise sweeps are more accurate, but also potentially slower than regular sweeps.
By default, precise sweeps are enabled.
\param[in] flag True/false to enable/disable precise sweeps.
*/
virtual void setPreciseSweeps(bool flag) = 0;
/**
\brief Enables or disables vertical sliding against ceilings.
Geometry is seen as "ceilings" when the following condition is met:
dot product(contact normal, up direction)<0.0f
This flag controls whether characters should slide vertically along the geometry in that case.
By default, sliding is allowed.
\param[in] flag True/false to enable/disable sliding.
*/
virtual void setPreventVerticalSlidingAgainstCeiling(bool flag) = 0;
/**
\brief Shift the origin of the character controllers and obstacle objects by the specified vector.
The positions of all character controllers, obstacle objects and the corresponding data structures will get adjusted to reflect the shifted origin location
(the shift vector will get subtracted from all character controller and obstacle object positions).
\note It is the user's responsibility to keep track of the summed total origin shift and adjust all input/output to/from PhysXCharacterKinematic accordingly.
\note This call will not automatically shift the PhysX scene and its objects. You need to call PxScene::shiftOrigin() seperately to keep the systems in sync.
\param[in] shift Translation vector to shift the origin by.
*/
virtual void shiftOrigin(const PxVec3& shift) = 0;
protected:
PxControllerManager() {}
virtual ~PxControllerManager() {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/**
\brief Creates the controller manager.
\param[in] scene PhysX scene.
\param[in] lockingEnabled Enables/disables internal locking.
The character controller is informed by #PxDeletionListener::onRelease() when actors or shapes are released, and updates its internal
caches accordingly. If character controller movement or a call to #PxControllerManager::shiftOrigin() may overlap with actor/shape releases,
internal data structures must be guarded against concurrent access.
Locking guarantees thread safety in such scenarios.
\note locking may result in significant slowdown for release of actors or shapes.
By default, locking is disabled.
*/
PX_C_EXPORT PX_PHYSX_CHARACTER_API physx::PxControllerManager* PX_CALL_CONV PxCreateControllerManager(physx::PxScene& scene, bool lockingEnabled = false);
/** @} */
#endif //PX_PHYSICS_CCT_MANAGER

View File

@ -0,0 +1,192 @@
//
// 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-2018 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_CCT_OBSTACLES
#define PX_PHYSICS_CCT_OBSTACLES
/** \addtogroup character
@{
*/
#include "characterkinematic/PxCharacter.h"
#include "characterkinematic/PxExtended.h"
#include "geometry/PxGeometry.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxControllerManager;
#define INVALID_OBSTACLE_HANDLE 0xffffffff
/**
\brief Base class for obstacles.
@see PxBoxObstacle PxCapsuleObstacle PxObstacleContext
*/
class PxObstacle
{
protected:
PxObstacle() :
mType (PxGeometryType::eINVALID),
mUserData (NULL),
mPos (0.0, 0.0, 0.0),
mRot (PxQuat(PxIdentity))
{}
PxGeometryType::Enum mType;
public:
PX_FORCE_INLINE PxGeometryType::Enum getType() const { return mType; }
void* mUserData;
PxExtendedVec3 mPos;
PxQuat mRot;
};
/**
\brief A box obstacle.
@see PxObstacle PxCapsuleObstacle PxObstacleContext
*/
class PxBoxObstacle : public PxObstacle
{
public:
PxBoxObstacle() :
mHalfExtents(0.0f)
{ mType = PxGeometryType::eBOX; }
PxVec3 mHalfExtents;
};
/**
\brief A capsule obstacle.
@see PxBoxObstacle PxObstacle PxObstacleContext
*/
class PxCapsuleObstacle : public PxObstacle
{
public:
PxCapsuleObstacle() :
mHalfHeight (0.0f),
mRadius (0.0f)
{ mType = PxGeometryType::eCAPSULE; }
PxReal mHalfHeight;
PxReal mRadius;
};
typedef PxU32 ObstacleHandle;
/**
\brief Context class for obstacles.
An obstacle context class contains and manages a set of user-defined obstacles.
@see PxBoxObstacle PxCapsuleObstacle PxObstacle
*/
class PxObstacleContext
{
public:
PxObstacleContext() {}
virtual ~PxObstacleContext() {}
/**
\brief Releases the context.
*/
virtual void release() = 0;
/**
\brief Retrieves the controller manager associated with this context.
\return The associated controller manager
*/
virtual PxControllerManager& getControllerManager() const = 0;
/**
\brief Adds an obstacle to the context.
\param [in] obstacle Obstacle data for the new obstacle. The data gets copied.
\return Handle for newly-added obstacle
*/
virtual ObstacleHandle addObstacle(const PxObstacle& obstacle) = 0;
/**
\brief Removes an obstacle from the context.
\param [in] handle Handle for the obstacle object that needs to be removed.
\return True if success
*/
virtual bool removeObstacle(ObstacleHandle handle) = 0;
/**
\brief Updates data for an existing obstacle.
\param [in] handle Handle for the obstacle object that needs to be updated.
\param [in] obstacle New obstacle data
\return True if success
*/
virtual bool updateObstacle(ObstacleHandle handle, const PxObstacle& obstacle) = 0;
/**
\brief Retrieves number of obstacles in the context.
\return Number of obstacles in the context
*/
virtual PxU32 getNbObstacles() const = 0;
/**
\brief Retrieves desired obstacle.
\param [in] i Obstacle index
\return Desired obstacle
*/
virtual const PxObstacle* getObstacle(PxU32 i) const = 0;
/**
\brief Retrieves desired obstacle by given handle.
\param [in] handle Obstacle handle
\return Desired obstacle
*/
virtual const PxObstacle* getObstacleByHandle(ObstacleHandle handle) const = 0;
};
#if !PX_DOXYGEN
}
#endif
/** @} */
#endif

View File

@ -0,0 +1,275 @@
//
// 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-2018 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_CCT_EXTENDED
#define PX_PHYSICS_CCT_EXTENDED
/** \addtogroup character
@{
*/
// This needs to be included in Foundation just for the debug renderer
#include "PxPhysXConfig.h"
#include "foundation/PxTransform.h"
#include "foundation/PxAssert.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
// This has to be done here since it also changes the top-level "Px" and "Np" APIs
#define PX_BIG_WORLDS
#ifdef PX_BIG_WORLDS
typedef double PxExtended;
#define PX_MAX_EXTENDED PX_MAX_F64
#define PxExtendedAbs(x) fabs(x)
struct PxExtendedVec3
{
PX_INLINE PxExtendedVec3() {}
PX_INLINE PxExtendedVec3(PxExtended _x, PxExtended _y, PxExtended _z) : x(_x), y(_y), z(_z) {}
PX_INLINE bool isZero() const
{
if(x!=0.0 || y!=0.0 || z!=0.0) return false;
return true;
}
PX_INLINE PxExtended dot(const PxVec3& v) const
{
return x * PxExtended(v.x) + y * PxExtended(v.y) + z * PxExtended(v.z);
}
PX_INLINE PxExtended distanceSquared(const PxExtendedVec3& v) const
{
PxExtended dx = x - v.x;
PxExtended dy = y - v.y;
PxExtended dz = z - v.z;
return dx * dx + dy * dy + dz * dz;
}
PX_INLINE PxExtended magnitudeSquared() const
{
return x * x + y * y + z * z;
}
PX_INLINE PxExtended magnitude() const
{
return PxSqrt(x * x + y * y + z * z);
}
PX_INLINE PxExtended normalize()
{
PxExtended m = magnitude();
if (m != 0.0)
{
const PxExtended il = PxExtended(1.0) / m;
x *= il;
y *= il;
z *= il;
}
return m;
}
PX_INLINE bool isFinite() const
{
return PxIsFinite(x) && PxIsFinite(y) && PxIsFinite(z);
}
PX_INLINE void maximum(const PxExtendedVec3& v)
{
if (x < v.x) x = v.x;
if (y < v.y) y = v.y;
if (z < v.z) z = v.z;
}
PX_INLINE void minimum(const PxExtendedVec3& v)
{
if (x > v.x) x = v.x;
if (y > v.y) y = v.y;
if (z > v.z) z = v.z;
}
PX_INLINE void set(PxExtended x_, PxExtended y_, PxExtended z_)
{
this->x = x_;
this->y = y_;
this->z = z_;
}
PX_INLINE void setPlusInfinity()
{
x = y = z = PX_MAX_EXTENDED;
}
PX_INLINE void setMinusInfinity()
{
x = y = z = -PX_MAX_EXTENDED;
}
PX_INLINE void cross(const PxExtendedVec3& left, const PxVec3& right)
{
// temps needed in case left or right is this.
PxExtended a = (left.y * PxExtended(right.z)) - (left.z * PxExtended(right.y));
PxExtended b = (left.z * PxExtended(right.x)) - (left.x * PxExtended(right.z));
PxExtended c = (left.x * PxExtended(right.y)) - (left.y * PxExtended(right.x));
x = a;
y = b;
z = c;
}
PX_INLINE void cross(const PxExtendedVec3& left, const PxExtendedVec3& right)
{
// temps needed in case left or right is this.
PxExtended a = (left.y * right.z) - (left.z * right.y);
PxExtended b = (left.z * right.x) - (left.x * right.z);
PxExtended c = (left.x * right.y) - (left.y * right.x);
x = a;
y = b;
z = c;
}
PX_INLINE PxExtendedVec3 cross(const PxExtendedVec3& v) const
{
PxExtendedVec3 temp;
temp.cross(*this,v);
return temp;
}
PX_INLINE void cross(const PxVec3& left, const PxExtendedVec3& right)
{
// temps needed in case left or right is this.
PxExtended a = (PxExtended(left.y) * right.z) - (PxExtended(left.z) * right.y);
PxExtended b = (PxExtended(left.z) * right.x) - (PxExtended(left.x) * right.z);
PxExtended c = (PxExtended(left.x) * right.y) - (PxExtended(left.y) * right.x);
x = a;
y = b;
z = c;
}
PX_INLINE PxExtendedVec3 operator-() const
{
return PxExtendedVec3(-x, -y, -z);
}
PX_INLINE PxExtendedVec3& operator+=(const PxExtendedVec3& v)
{
x += v.x;
y += v.y;
z += v.z;
return *this;
}
PX_INLINE PxExtendedVec3& operator-=(const PxExtendedVec3& v)
{
x -= v.x;
y -= v.y;
z -= v.z;
return *this;
}
PX_INLINE PxExtendedVec3& operator+=(const PxVec3& v)
{
x += PxExtended(v.x);
y += PxExtended(v.y);
z += PxExtended(v.z);
return *this;
}
PX_INLINE PxExtendedVec3& operator-=(const PxVec3& v)
{
x -= PxExtended(v.x);
y -= PxExtended(v.y);
z -= PxExtended(v.z);
return *this;
}
PX_INLINE PxExtendedVec3& operator*=(const PxReal& s)
{
x *= PxExtended(s);
y *= PxExtended(s);
z *= PxExtended(s);
return *this;
}
PX_INLINE PxExtendedVec3 operator+(const PxExtendedVec3& v) const
{
return PxExtendedVec3(x + v.x, y + v.y, z + v.z);
}
PX_INLINE PxVec3 operator-(const PxExtendedVec3& v) const
{
return PxVec3(PxReal(x - v.x), PxReal(y - v.y), PxReal(z - v.z));
}
PX_INLINE PxExtended& operator[](int index)
{
PX_ASSERT(index>=0 && index<=2);
return reinterpret_cast<PxExtended*>(this)[index];
}
PX_INLINE PxExtended operator[](int index) const
{
PX_ASSERT(index>=0 && index<=2);
return reinterpret_cast<const PxExtended*>(this)[index];
}
PxExtended x,y,z;
};
PX_FORCE_INLINE PxVec3 toVec3(const PxExtendedVec3& v)
{
return PxVec3(float(v.x), float(v.y), float(v.z));
}
#else
// Big worlds not defined
typedef PxVec3 PxExtendedVec3;
typedef PxReal PxExtended;
#define PX_MAX_EXTENDED PX_MAX_F32
#define PxExtendedAbs(x) fabsf(x)
#endif
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,85 @@
//
// 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-2018 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_COLLISION_DEFS_H
#define PX_COLLISION_DEFS_H
#include "PxPhysXConfig.h"
#include "foundation/PxVec3.h"
#include "foundation/PxMat33.h"
#include "geomutils/GuContactPoint.h"
#include "geomutils/GuContactBuffer.h"
#include "geometry/PxGeometry.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief A structure to cache contact information produced by LL contact gen functions.
*/
struct PxCache
{
PxU8* mCachedData; //!< Cached data pointer. Allocated via PxCacheAllocator
PxU16 mCachedSize; //!< The total size of the cached data
PxU8 mPairData; //!< Pair data information used and cached internally by some contact gen functions to accelerate performance.
PxU8 mManifoldFlags; //!< Manifold flags used to identify the format the cached data is stored in.
PxCache() : mCachedData(NULL), mCachedSize(0), mPairData(0), mManifoldFlags(0)
{
}
};
/**
A callback class to allocate memory to cache information used in contact generation.
*/
class PxCacheAllocator
{
public:
/**
\brief Allocates cache data for contact generation. This data is stored inside PxCache objects. The application can retain and provide this information for future contact generation passes
for a given pair to improve contact generation performance. It is the application's responsibility to release this memory appropriately. If the memory is released, the application must ensure that
this memory is no longer referenced by any PxCache objects passed to PxGenerateContacts.
\param byteSize The size of the allocation in bytes
\return the newly-allocated memory. The returned address must be 16-byte aligned.
*/
virtual PxU8* allocateCacheData(const PxU32 byteSize) = 0;
virtual ~PxCacheAllocator() {}
};
#if !PX_DOXYGEN
}
#endif
#endif

View File

@ -0,0 +1,201 @@
//
// 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-2018 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_PX_BASE
#define PX_PHYSICS_PX_BASE
/** \addtogroup common
@{
*/
#include "PxSerialFramework.h"
#include "PxCollection.h"
#include "common/PxTypeInfo.h"
#include "foundation/PxFlags.h"
#include <string.h> // For strcmp
#if !PX_DOXYGEN
namespace physx
{
#endif
typedef PxU16 PxType;
/**
\brief Flags for PxBase.
*/
struct PxBaseFlag
{
enum Enum
{
eOWNS_MEMORY = (1<<0),
eIS_RELEASABLE = (1<<1)
};
};
typedef PxFlags<PxBaseFlag::Enum, PxU16> PxBaseFlags;
PX_FLAGS_OPERATORS(PxBaseFlag::Enum, PxU16)
/**
\brief Base class for objects that can be members of a PxCollection.
All PxBase sub-classes can be serialized.
@see PxCollection
*/
class PxBase
{
//= ATTENTION! =====================================================================================
// Changing the data layout of this class breaks the binary serialization format. See comments for
// PX_BINARY_SERIAL_VERSION. If a modification is required, please adjust the getBinaryMetaData
// function. If the modification is made on a custom branch, please change PX_BINARY_SERIAL_VERSION
// accordingly.
//==================================================================================================
public:
/**
\brief Releases the PxBase instance, please check documentation of release in derived class.
*/
virtual void release() = 0;
/**
\brief Returns string name of dynamic type.
\return Class name of most derived type of this object.
*/
virtual const char* getConcreteTypeName() const = 0;
/* brief Implements dynamic cast functionality.
Example use:
if(actor->is<PxRigidDynamic>()) {...}
\return A pointer to the specified type if object matches, otherwise NULL
*/
template<class T> T* is() { return typeMatch<T>() ? static_cast<T*>(this) : NULL; }
/* brief Implements dynamic cast functionality for const objects.
Example use:
if(actor->is<PxRigidDynamic>()) {...}
\return A pointer to the specified type if object matches, otherwise NULL
*/
template<class T> const T* is() const { return typeMatch<T>() ? static_cast<const T*>(this) : NULL; }
/**
\brief Returns concrete type of object.
\return PxConcreteType::Enum of serialized object
@see PxConcreteType
*/
PX_FORCE_INLINE PxType getConcreteType() const { return mConcreteType; }
/**
\brief Set PxBaseFlag
\param[in] flag The flag to be set
\param[in] value The flags new value
*/
PX_FORCE_INLINE void setBaseFlag(PxBaseFlag::Enum flag, bool value) { mBaseFlags = value ? mBaseFlags|flag : mBaseFlags&~flag; }
/**
\brief Set PxBaseFlags
\param[in] inFlags The flags to be set
@see PxBaseFlags
*/
PX_FORCE_INLINE void setBaseFlags(PxBaseFlags inFlags) { mBaseFlags = inFlags; }
/**
\brief Returns PxBaseFlags
\return PxBaseFlags
@see PxBaseFlags
*/
PX_FORCE_INLINE PxBaseFlags getBaseFlags() const { return mBaseFlags; }
/**
\brief Whether the object is subordinate.
A class is subordinate, if it can only be instantiated in the context of another class.
\return Whether the class is subordinate
@see PxSerialization::isSerializable
*/
virtual bool isReleasable() const { return mBaseFlags & PxBaseFlag::eIS_RELEASABLE; }
protected:
/**
\brief Constructor setting concrete type and base flags.
*/
PX_INLINE PxBase(PxType concreteType, PxBaseFlags baseFlags)
: mConcreteType(concreteType), mBaseFlags(baseFlags) {}
/**
\brief Deserialization constructor setting base flags.
*/
PX_INLINE PxBase(PxBaseFlags baseFlags) : mBaseFlags(baseFlags) {}
/**
\brief Destructor.
*/
virtual ~PxBase() {}
/**
\brief Returns whether a given type name matches with the type of this instance
*/
virtual bool isKindOf(const char* superClass) const { return !::strcmp(superClass, "PxBase"); }
template<class T> bool typeMatch() const
{
return PxU32(PxTypeInfo<T>::eFastTypeId)!=PxU32(PxConcreteType::eUNDEFINED) ?
PxU32(getConcreteType()) == PxU32(PxTypeInfo<T>::eFastTypeId) : isKindOf(PxTypeInfo<T>::name());
}
private:
friend void getBinaryMetaData_PxBase(PxOutputStream& stream);
protected:
PxType mConcreteType; // concrete type identifier - see PxConcreteType.
PxBaseFlags mBaseFlags; // internal flags
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,279 @@
//
// 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-2018 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_PX_COLLECTION
#define PX_PHYSICS_PX_COLLECTION
#include "PxSerialFramework.h"
/** \addtogroup common
@{
*/
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxBase;
/**
\brief Collection class for serialization.
A collection is a set of PxBase objects. PxBase objects can be added to the collection
regardless of other objects they depend on. Objects may be named using PxSerialObjectId values in order
to resolve dependencies between objects of different collections.
Serialization and deserialization only work through collections.
A scene is typically serialized using the following steps:
-# create a serialization registry
-# create a collection for scene objects
-# complete the scene objects (adds all dependent objects, e.g. meshes)
-# serialize collection
-# release collection
-# release serialization registry
For example the code may look like this:
\code
PxPhysics* physics; // The physics
PxScene* scene; // The physics scene
SerialStream s; // The user-defined stream doing the actual write to disk
PxSerializationRegistry* registry = PxSerialization::createSerializationRegistry(*physics); // step 1)
PxCollection* collection = PxSerialization::createCollection(*scene); // step 2)
PxSerialization::complete(*collection, *registry); // step 3)
PxSerialization::serializeCollectionToBinary(s, *collection, *registry); // step 4)
collection->release(); // step 5)
registry->release(); // step 6)
\endcode
A scene is typically deserialized using the following steps:
-# load a serialized collection into memory
-# create a serialization registry
-# create a collection by passing the serialized memory block
-# add collected objects to scene
-# release collection
-# release serialization registry
For example the code may look like this:
\code
PxPhysics* physics; // The physics
PxScene* scene; // The physics scene
void* memory128; // a 128-byte aligned buffer previously loaded from disk by the user - step 1)
PxSerializationRegistry* registry = PxSerialization::createSerializationRegistry(*physics); // step 2)
PxCollection* collection = PxSerialization::createCollectionFromBinary(memory128, *registry); // step 3)
scene->addCollection(*collection); // step 4)
collection->release(); // step 5)
registry->release(); // step 6)
\endcode
@see PxBase, PxCreateCollection()
*/
class PxCollection
{
public:
/**
\brief Adds a PxBase object to the collection.
Adds a PxBase object to the collection. Optionally a PxSerialObjectId can be provided
in order to resolve dependencies between collections. A PxSerialObjectId value of PX_SERIAL_OBJECT_ID_INVALID
means the object remains without id. Objects can be added regardless of other objects they require. If the object
is already in the collection, the ID will be set if it was PX_SERIAL_OBJECT_ID_INVALID previously, otherwise the
operation fails.
\param[in] object Object to be added to the collection
\param[in] id Optional PxSerialObjectId id
*/
virtual void add(PxBase& object, PxSerialObjectId id = PX_SERIAL_OBJECT_ID_INVALID) = 0;
/**
\brief Removes a PxBase member object from the collection.
Object needs to be contained by the collection.
\param[in] object PxBase object to be removed
*/
virtual void remove(PxBase& object) = 0;
/**
\brief Returns whether the collection contains a certain PxBase object.
\param[in] object PxBase object
\return Whether object is contained.
*/
virtual bool contains(PxBase& object) const = 0;
/**
\brief Adds an id to a member PxBase object.
If the object is already associated with an id within the collection, the id is replaced.
May only be called for objects that are members of the collection. The id needs to be unique
within the collection.
\param[in] object Member PxBase object
\param[in] id PxSerialObjectId id to be given to the object
*/
virtual void addId(PxBase& object, PxSerialObjectId id) = 0;
/**
\brief Removes id from a contained PxBase object.
May only be called for ids that are associated with an object in the collection.
\param[in] id PxSerialObjectId value
*/
virtual void removeId(PxSerialObjectId id) = 0;
/**
\brief Adds all PxBase objects and their ids of collection to this collection.
PxBase objects already in this collection are ignored. Object ids need to be conflict
free, i.e. the same object may not have two different ids within the two collections.
\param[in] collection Collection to be added
*/
virtual void add(PxCollection& collection) = 0;
/**
\brief Removes all PxBase objects of collection from this collection.
PxBase objects not present in this collection are ignored. Ids of objects
which are removed are also removed.
\param[in] collection Collection to be removed
*/
virtual void remove(PxCollection& collection) = 0;
/**
\brief Gets number of PxBase objects in this collection.
\return Number of objects in this collection
*/
virtual PxU32 getNbObjects() const = 0;
/**
\brief Gets the PxBase object of this collection given its index.
\param[in] index PxBase index in [0, getNbObjects())
\return PxBase object at index index
*/
virtual PxBase& getObject(PxU32 index) const = 0;
/**
\brief Copies member PxBase pointers to a user specified buffer.
\param[out] userBuffer Array of PxBase pointers
\param[in] bufferSize Capacity of userBuffer
\param[in] startIndex Offset into list of member PxBase objects
\return number of members PxBase objects that have been written to the userBuffer
*/
virtual PxU32 getObjects(PxBase** userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
/**
\brief Looks for a PxBase object given a PxSerialObjectId value.
If there is no PxBase object in the collection with the given id, NULL is returned.
\param[in] id PxSerialObjectId value to look for
\return PxBase object with the given id value or NULL
*/
virtual PxBase* find(PxSerialObjectId id) const = 0;
/**
\brief Gets number of PxSerialObjectId names in this collection.
\return Number of PxSerialObjectId names in this collection
*/
virtual PxU32 getNbIds() const = 0;
/**
\brief Copies member PxSerialObjectId values to a user specified buffer.
\param[out] userBuffer Array of PxSerialObjectId values
\param[in] bufferSize Capacity of userBuffer
\param[in] startIndex Offset into list of member PxSerialObjectId values
\return number of members PxSerialObjectId values that have been written to the userBuffer
*/
virtual PxU32 getIds(PxSerialObjectId* userBuffer, PxU32 bufferSize, PxU32 startIndex=0) const = 0;
/**
\brief Gets the PxSerialObjectId name of a PxBase object within the collection.
The PxBase object needs to be a member of the collection.
\param[in] object PxBase object to get id for
\return PxSerialObjectId name of the object or PX_SERIAL_OBJECT_ID_INVALID if the object is unnamed
*/
virtual PxSerialObjectId getId(const PxBase& object) const = 0;
/**
\brief Deletes a collection object.
This function only deletes the collection object, i.e. the container class. It doesn't delete objects
that are part of the collection.
@see PxCreateCollection()
*/
virtual void release() = 0;
protected:
PxCollection() {}
virtual ~PxCollection() {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/**
\brief Creates a collection object.
Objects can only be serialized or deserialized through a collection.
For serialization, users must add objects to the collection and serialize the collection as a whole.
For deserialization, the system gives back a collection of deserialized objects to users.
\return The new collection object.
@see PxCollection, PxCollection::release()
*/
PX_PHYSX_COMMON_API physx::PxCollection* PX_CALL_CONV PxCreateCollection();
/** @} */
#endif

View File

@ -0,0 +1,211 @@
//
// 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-2018 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_CORE_UTILTY_TYPES_H
#define PX_CORE_UTILTY_TYPES_H
/** \addtogroup common
@{
*/
#include "foundation/PxAssert.h"
#include "foundation/PxMemory.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
struct PxStridedData
{
/**
\brief The offset in bytes between consecutive samples in the data.
<b>Default:</b> 0
*/
PxU32 stride;
const void* data;
PxStridedData() : stride( 0 ), data( NULL ) {}
template<typename TDataType>
PX_INLINE const TDataType& at( PxU32 idx ) const
{
PxU32 theStride( stride );
if ( theStride == 0 )
theStride = sizeof( TDataType );
PxU32 offset( theStride * idx );
return *(reinterpret_cast<const TDataType*>( reinterpret_cast< const PxU8* >( data ) + offset ));
}
};
template<typename TDataType>
struct PxTypedStridedData
{
PxU32 stride;
const TDataType* data;
PxTypedStridedData()
: stride( 0 )
, data( NULL )
{
}
};
struct PxBoundedData : public PxStridedData
{
PxU32 count;
PxBoundedData() : count( 0 ) {}
};
template<PxU8 TNumBytes>
struct PxPadding
{
PxU8 mPadding[TNumBytes];
PxPadding()
{
for ( PxU8 idx =0; idx < TNumBytes; ++idx )
mPadding[idx] = 0;
}
};
template <PxU32 NB_ELEMENTS> class PxFixedSizeLookupTable
{
//= ATTENTION! =====================================================================================
// Changing the data layout of this class breaks the binary serialization format. See comments for
// PX_BINARY_SERIAL_VERSION. If a modification is required, please adjust the getBinaryMetaData
// function. If the modification is made on a custom branch, please change PX_BINARY_SERIAL_VERSION
// accordingly.
//==================================================================================================
public:
PxFixedSizeLookupTable()
: mNbDataPairs(0)
{
}
PxFixedSizeLookupTable(const PxEMPTY) {}
PxFixedSizeLookupTable(const PxReal* dataPairs, const PxU32 numDataPairs)
{
PxMemCopy(mDataPairs,dataPairs,sizeof(PxReal)*2*numDataPairs);
mNbDataPairs=numDataPairs;
}
PxFixedSizeLookupTable(const PxFixedSizeLookupTable& src)
{
PxMemCopy(mDataPairs,src.mDataPairs,sizeof(PxReal)*2*src.mNbDataPairs);
mNbDataPairs=src.mNbDataPairs;
}
~PxFixedSizeLookupTable()
{
}
PxFixedSizeLookupTable& operator=(const PxFixedSizeLookupTable& src)
{
PxMemCopy(mDataPairs,src.mDataPairs,sizeof(PxReal)*2*src.mNbDataPairs);
mNbDataPairs=src.mNbDataPairs;
return *this;
}
PX_FORCE_INLINE void addPair(const PxReal x, const PxReal y)
{
PX_ASSERT(mNbDataPairs<NB_ELEMENTS);
mDataPairs[2*mNbDataPairs+0]=x;
mDataPairs[2*mNbDataPairs+1]=y;
mNbDataPairs++;
}
PX_FORCE_INLINE PxReal getYVal(const PxReal x) const
{
if(0==mNbDataPairs)
{
PX_ASSERT(false);
return 0;
}
if(1==mNbDataPairs || x<getX(0))
{
return getY(0);
}
PxReal x0=getX(0);
PxReal y0=getY(0);
for(PxU32 i=1;i<mNbDataPairs;i++)
{
const PxReal x1=getX(i);
const PxReal y1=getY(i);
if((x>=x0)&&(x<x1))
{
return (y0+(y1-y0)*(x-x0)/(x1-x0));
}
x0=x1;
y0=y1;
}
PX_ASSERT(x>=getX(mNbDataPairs-1));
return getY(mNbDataPairs-1);
}
PxU32 getNbDataPairs() const {return mNbDataPairs;}
void clear()
{
memset(mDataPairs, 0, NB_ELEMENTS*2*sizeof(PxReal));
mNbDataPairs = 0;
}
PX_FORCE_INLINE PxReal getX(const PxU32 i) const
{
return mDataPairs[2*i];
}
PX_FORCE_INLINE PxReal getY(const PxU32 i) const
{
return mDataPairs[2*i+1];
}
PxReal mDataPairs[2*NB_ELEMENTS];
PxU32 mNbDataPairs;
PxU32 mPad[3];
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,228 @@
//
// 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-2018 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_METADATA_H
#define PX_PHYSICS_METADATA_H
/** \addtogroup physics
@{
*/
#include "foundation/Px.h"
#include "foundation/PxIO.h"
#include "PxMetaDataFlags.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Struct to store meta data definitions.
Note: The individual fields have different meaning depending on the meta data entry configuration.
*/
struct PxMetaDataEntry
{
const char* type; //!< Field type (bool, byte, quaternion, etc)
const char* name; //!< Field name (appears exactly as in the source file)
PxU32 offset; //!< Offset from the start of the class (ie from "this", field is located at "this"+Offset)
PxU32 size; //!< sizeof(Type)
PxU32 count; //!< Number of items of type Type (0 for dynamic sizes)
PxU32 offsetSize; //!< Offset of dynamic size param, for dynamic arrays
PxU32 flags; //!< Field parameters
PxU32 alignment; //!< Explicit alignment
};
#define PX_STORE_METADATA(stream, metaData) stream.write(&metaData, sizeof(PxMetaDataEntry))
#define PX_SIZE_OF(Class, Member) sizeof((reinterpret_cast<Class*>(0))->Member)
/**
\brief specifies a binary metadata entry for a member variable of a class
*/
#define PX_DEF_BIN_METADATA_ITEM(stream, Class, type, name, flags) \
{ \
PxMetaDataEntry tmp = { #type, #name, PxU32(PX_OFFSET_OF_RT(Class, name)), PX_SIZE_OF(Class, name), \
1, 0, flags, 0}; \
PX_STORE_METADATA(stream, tmp); \
}
/**
\brief specifies a binary metadata entry for a member array variable of a class
\details similar to PX_DEF_BIN_METADATA_ITEMS_AUTO but for cases with mismatch between specified type and array type
*/
#define PX_DEF_BIN_METADATA_ITEMS(stream, Class, type, name, flags, count) \
{ \
PxMetaDataEntry tmp = { #type, #name, PxU32(PX_OFFSET_OF_RT(Class, name)), PX_SIZE_OF(Class, name), \
count, 0, flags, 0}; \
PX_STORE_METADATA(stream, tmp); \
}
/**
\brief specifies a binary metadata entry for a member array variable of a class
\details similar to PX_DEF_BIN_METADATA_ITEMS but automatically detects the array length, which only works when the specified
type matches the type of the array - does not support PxMetaDataFlag::ePTR
*/
#define PX_DEF_BIN_METADATA_ITEMS_AUTO(stream, Class, type, name, flags) \
{ \
PxMetaDataEntry tmp = { #type, #name, PxU32(PX_OFFSET_OF_RT(Class, name)), PX_SIZE_OF(Class, name), \
sizeof((reinterpret_cast<Class*>(0))->name)/sizeof(type), 0, flags, 0}; \
PX_STORE_METADATA(stream, tmp); \
}
/**
\brief specifies a binary metadata entry for a class
*/
#define PX_DEF_BIN_METADATA_CLASS(stream, Class) \
{ \
PxMetaDataEntry tmp = { #Class, 0, 0, sizeof(Class), 0, 0, PxMetaDataFlag::eCLASS, 0 }; \
PX_STORE_METADATA(stream, tmp); \
}
/**
\brief specifies a binary metadata entry for a virtual class
*/
#define PX_DEF_BIN_METADATA_VCLASS(stream, Class) \
{ \
PxMetaDataEntry tmp = { #Class, 0, 0, sizeof(Class), 0, 0, PxMetaDataFlag::eCLASS|PxMetaDataFlag::eVIRTUAL, 0}; \
PX_STORE_METADATA(stream, tmp); \
}
/**
\brief specifies a binary metadata entry for a typedef
*/
#define PX_DEF_BIN_METADATA_TYPEDEF(stream, newType, oldType) \
{ \
PxMetaDataEntry tmp = { #newType, #oldType, 0, 0, 0, 0, PxMetaDataFlag::eTYPEDEF, 0 }; \
PX_STORE_METADATA(stream, tmp); \
}
/**
\brief specifies a binary metadata entry for declaring a base class
*/
#define PX_DEF_BIN_METADATA_BASE_CLASS(stream, Class, BaseClass) \
{ \
Class* myClass = reinterpret_cast<Class*>(42); \
BaseClass* s = static_cast<BaseClass*>(myClass); \
const PxU32 offset = PxU32(size_t(s) - size_t(myClass)); \
PxMetaDataEntry tmp = { #Class, #BaseClass, offset, sizeof(Class), 0, 0, PxMetaDataFlag::eCLASS, 0 }; \
PX_STORE_METADATA(stream, tmp); \
}
/**
\brief specifies a binary metadata entry for a union
*/
#define PX_DEF_BIN_METADATA_UNION(stream, Class, name) \
{ \
PxMetaDataEntry tmp = { #Class, 0, PxU32(PX_OFFSET_OF_RT(Class, name)), PX_SIZE_OF(Class, name), \
1, 0, PxMetaDataFlag::eUNION, 0 }; \
PX_STORE_METADATA(stream, tmp); \
}
/**
\brief specifies a binary metadata entry for a particular member type of a union
*/
#define PX_DEF_BIN_METADATA_UNION_TYPE(stream, Class, type, enumValue) \
{ \
PxMetaDataEntry tmp = { #Class, #type, enumValue, 0, 0, 0, PxMetaDataFlag::eUNION, 0 }; \
PX_STORE_METADATA(stream, tmp); \
}
/**
\brief specifies a binary metadata entry for extra data
*/
#define PX_DEF_BIN_METADATA_EXTRA_ITEM(stream, Class, type, control, align) \
{ \
PxMetaDataEntry tmp = { #type, 0, PxU32(PX_OFFSET_OF_RT(Class, control)), sizeof(type), 0, PxU32(PX_SIZE_OF(Class, control)), \
PxMetaDataFlag::eEXTRA_DATA|PxMetaDataFlag::eEXTRA_ITEM, align }; \
PX_STORE_METADATA(stream, tmp); \
}
/**
\brief specifies a binary metadata entry for an array of extra data
*/
#define PX_DEF_BIN_METADATA_EXTRA_ITEMS(stream, Class, type, control, count, flags, align) \
{ \
PxMetaDataEntry tmp = { #type, 0, PxU32(PX_OFFSET_OF_RT(Class, control)), PxU32(PX_SIZE_OF(Class, control)), \
PxU32(PX_OFFSET_OF_RT(Class, count)), PxU32(PX_SIZE_OF(Class, count)), \
PxMetaDataFlag::eEXTRA_DATA|PxMetaDataFlag::eEXTRA_ITEMS|flags, align }; \
PX_STORE_METADATA(stream, tmp); \
}
/**
\brief specifies a binary metadata entry for an array of extra data
additional to PX_DEF_BIN_METADATA_EXTRA_ITEMS a mask can be specified to interpret the control value
@see PxMetaDataFlag::eCONTROL_MASK
*/
#define PX_DEF_BIN_METADATA_EXTRA_ITEMS_MASKED_CONTROL(stream, Class, type, control, controlMask ,count, flags, align) \
{ \
PxMetaDataEntry tmp = { #type, 0, PxU32(PX_OFFSET_OF_RT(Class, control)), PxU32(PX_SIZE_OF(Class, control)), \
PxU32(PX_OFFSET_OF_RT(Class, count)), PxU32(PX_SIZE_OF(Class, count)), \
PxMetaDataFlag::eCONTROL_MASK|PxMetaDataFlag::eEXTRA_DATA|PxMetaDataFlag::eEXTRA_ITEMS|flags|(controlMask & PxMetaDataFlag::eCONTROL_MASK_RANGE) << 16, \
align}; \
PX_STORE_METADATA(stream, tmp); \
}
/**
\brief specifies a binary metadata entry for an array of extra data
\details similar to PX_DEF_BIN_METADATA_EXTRA_ITEMS, but supporting no control - PxMetaDataFlag::ePTR is also not supported
*/
#define PX_DEF_BIN_METADATA_EXTRA_ARRAY(stream, Class, type, dyn_count, align, flags) \
{ \
PxMetaDataEntry tmp = { #type, 0, PxU32(PX_OFFSET_OF_RT(Class, dyn_count)), PX_SIZE_OF(Class, dyn_count), align, 0, \
PxMetaDataFlag::eEXTRA_DATA|flags, align }; \
PX_STORE_METADATA(stream, tmp); \
}
/**
\brief specifies a binary metadata entry for an string of extra data
*/
#define PX_DEF_BIN_METADATA_EXTRA_NAME(stream, Class, control, align) \
{ \
PxMetaDataEntry tmp = { "char", "string", 0, 0, 0, 0, PxMetaDataFlag::eEXTRA_DATA|PxMetaDataFlag::eEXTRA_NAME, align }; \
PX_STORE_METADATA(stream, tmp); \
}
/**
\brief specifies a binary metadata entry declaring an extra data alignment for a class
*/
#define PX_DEF_BIN_METADATA_EXTRA_ALIGN(stream, Class, align) \
{ \
PxMetaDataEntry tmp = { "PxU8", "Alignment", 0, 0, 0, 0, PxMetaDataFlag::eEXTRA_DATA|PxMetaDataFlag::eALIGNMENT, align}; \
PX_STORE_METADATA(stream, tmp); \
}
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,74 @@
//
// 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-2018 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_METADATA_FLAGS
#define PX_PHYSICS_METADATA_FLAGS
#include "foundation/Px.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Flags used to configure binary meta data entries, typically set through PX_DEF_BIN_METADATA defines.
@see PxMetaDataEntry
*/
struct PxMetaDataFlag
{
enum Enum
{
eCLASS = (1<<0), //!< declares a class
eVIRTUAL = (1<<1), //!< declares class to be virtual
eTYPEDEF = (1<<2), //!< declares a typedef
ePTR = (1<<3), //!< declares a pointer
eEXTRA_DATA = (1<<4), //!< declares extra data exported with PxSerializer::exportExtraData
eEXTRA_ITEM = (1<<5), //!< specifies one element of extra data
eEXTRA_ITEMS = (1<<6), //!< specifies an array of extra data
eEXTRA_NAME = (1<<7), //!< specifies a name of extra data
eUNION = (1<<8), //!< declares a union
ePADDING = (1<<9), //!< declares explicit padding data
eALIGNMENT = (1<<10), //!< declares aligned data
eCOUNT_MASK_MSB = (1<<11), //!< specifies that the count value's most significant bit needs to be masked out
eCOUNT_SKIP_IF_ONE = (1<<12), //!< specifies that the count value is treated as zero for a variable value of one - special case for single triangle meshes
eCONTROL_FLIP = (1<<13), //!< specifies that the control value is the negate of the variable value
eCONTROL_MASK = (1<<14), //!< specifies that the control value is masked - mask bits are assumed to be within eCONTROL_MASK_RANGE
eCONTROL_MASK_RANGE = 0x000000FF, //!< mask range allowed for eCONTROL_MASK
eFORCE_DWORD = 0x7fffffff
};
};
#if !PX_DOXYGEN
}
#endif
#endif

View File

@ -0,0 +1,124 @@
//
// 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-2018 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_COMMON_NX
#define PX_PHYSICS_COMMON_NX
/** \addtogroup common
@{ */
#include "foundation/Px.h"
/*Disable support for VS2017 prior version 15.5.1 for windows platform, because of a compiler bug:
https://developercommunity.visualstudio.com/content/problem/66047/possible-compiler-bug.html
*/
#if (PX_VC == 15) && PX_WINDOWS && (_MSC_FULL_VER < 191225830)
#error Visual studio 2017 prior to 15.5.1 is not supported because of a compiler bug.
#endif
// define API function declaration (public API only needed because of extensions)
#if defined PX_PHYSX_STATIC_LIB || defined PX_PHYSX_CORE_STATIC_LIB
#define PX_PHYSX_CORE_API
#else
#if PX_WINDOWS
#if defined PX_PHYSX_CORE_EXPORTS
#define PX_PHYSX_CORE_API __declspec(dllexport)
#else
#define PX_PHYSX_CORE_API __declspec(dllimport)
#endif
#elif PX_UNIX_FAMILY
#define PX_PHYSX_CORE_API PX_UNIX_EXPORT
#else
#define PX_PHYSX_CORE_API
#endif
#endif
#if PX_SUPPORT_GPU_PHYSX
// define API function declaration
#if defined PX_PHYSX_GPU_STATIC
#define PX_PHYSX_GPU_API
#else
#if PX_WINDOWS
#if defined PX_PHYSX_GPU_EXPORTS
#define PX_PHYSX_GPU_API __declspec(dllexport)
#else
#define PX_PHYSX_GPU_API __declspec(dllimport)
#endif
#elif PX_UNIX_FAMILY
#define PX_PHYSX_GPU_API PX_UNIX_EXPORT
#else
#define PX_PHYSX_GPU_API
#endif
#endif
#else // PX_SUPPORT_GPU_PHYSX
#define PX_PHYSX_GPU_API
#endif // PX_SUPPORT_GPU_PHYSX
#if defined PX_PHYSX_STATIC_LIB || defined PX_PHYSX_CORE_STATIC_LIB
#define PX_PHYSX_COMMON_API
#else
#if PX_WINDOWS && !defined(__CUDACC__)
#if defined PX_PHYSX_COMMON_EXPORTS
#define PX_PHYSX_COMMON_API __declspec(dllexport)
#else
#define PX_PHYSX_COMMON_API __declspec(dllimport)
#endif
#elif PX_UNIX_FAMILY
#define PX_PHYSX_COMMON_API PX_UNIX_EXPORT
#else
#define PX_PHYSX_COMMON_API
#endif
#endif
// Changing these parameters requires recompilation of the SDK
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxCollection;
class PxBase;
class PxHeightField;
class PxHeightFieldDesc;
class PxTriangleMesh;
class PxConvexMesh;
typedef PxU32 PxTriangleID;
typedef PxU16 PxMaterialTableIndex;
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,84 @@
//
// 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-2018 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_PX_PHYSICS_INSERTION_CALLBACK
#define PX_PHYSICS_PX_PHYSICS_INSERTION_CALLBACK
#include "PxBase.h"
/** \addtogroup common
@{
*/
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Callback interface that permits PxCooking to insert a
TriangleMesh, HeightfieldMesh or ConvexMesh directly into PxPhysics without the need to store
the cooking results into a stream.
Using this is advised only if real-time cooking is required; using "offline" cooking and
streams is otherwise preferred.
The default PxPhysicsInsertionCallback implementation must be used. The PxPhysics
default callback can be obtained using the PxPhysics::getPhysicsInsertionCallback().
@see PxCooking PxPhysics
*/
class PxPhysicsInsertionCallback
{
public:
PxPhysicsInsertionCallback() {}
/**
\brief Builds object (TriangleMesh, HeightfieldMesh or ConvexMesh) from given data in PxPhysics.
\param type Object type to build.
\param data Object data
\return PxBase Created object in PxPhysics.
*/
virtual PxBase* buildObjectFromData(PxConcreteType::Enum type, void* data) = 0;
protected:
virtual ~PxPhysicsInsertionCallback() {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,51 @@
//
// 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-2018 NVIDIA Corporation. All rights reserved.
#ifndef PXFOUNDATION_PXPROFILEZONE_H
#define PXFOUNDATION_PXPROFILEZONE_H
#include "foundation/PxProfiler.h"
#include "PxFoundation.h"
#if PX_DEBUG || PX_CHECKED || PX_PROFILE
#define PX_PROFILE_ZONE(x, y) \
physx::PxProfileScoped PX_CONCAT(_scoped, __LINE__)(PxGetProfilerCallback(), x, false, y)
#define PX_PROFILE_START_CROSSTHREAD(x, y) \
if(PxGetProfilerCallback()) \
PxGetProfilerCallback()->zoneStart(x, true, y)
#define PX_PROFILE_STOP_CROSSTHREAD(x, y) \
if(PxGetProfilerCallback()) \
PxGetProfilerCallback()->zoneEnd(NULL, x, true, y)
#else
#define PX_PROFILE_ZONE(x, y)
#define PX_PROFILE_START_CROSSTHREAD(x, y)
#define PX_PROFILE_STOP_CROSSTHREAD(x, y)
#endif
#define PX_PROFILE_POINTER_TO_U64(pointer) static_cast<uint64_t>(reinterpret_cast<size_t>(pointer))
#endif // PXFOUNDATION_PXPROFILEZONE_H

View File

@ -0,0 +1,157 @@
//
// 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-2018 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_FOUNDATION_PXRENDERBUFFER_H
#define PX_FOUNDATION_PXRENDERBUFFER_H
/** \addtogroup common
@{
*/
#include "common/PxPhysXCommonConfig.h"
#include "foundation/PxVec3.h"
#include "foundation/PxMat33.h"
#include "foundation/PxBounds3.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Default color values used for debug rendering.
*/
struct PxDebugColor
{
enum Enum
{
eARGB_BLACK = 0xff000000,
eARGB_RED = 0xffff0000,
eARGB_GREEN = 0xff00ff00,
eARGB_BLUE = 0xff0000ff,
eARGB_YELLOW = 0xffffff00,
eARGB_MAGENTA = 0xffff00ff,
eARGB_CYAN = 0xff00ffff,
eARGB_WHITE = 0xffffffff,
eARGB_GREY = 0xff808080,
eARGB_DARKRED = 0x88880000,
eARGB_DARKGREEN = 0x88008800,
eARGB_DARKBLUE = 0x88000088
};
};
/**
\brief Used to store a single point and colour for debug rendering.
*/
struct PxDebugPoint
{
PxDebugPoint(const PxVec3& p, const PxU32& c)
: pos(p), color(c) {}
PxVec3 pos;
PxU32 color;
};
/**
\brief Used to store a single line and colour for debug rendering.
*/
struct PxDebugLine
{
PxDebugLine(const PxVec3& p0, const PxVec3& p1, const PxU32& c)
: pos0(p0), color0(c), pos1(p1), color1(c) {}
PxVec3 pos0;
PxU32 color0;
PxVec3 pos1;
PxU32 color1;
};
/**
\brief Used to store a single triangle and colour for debug rendering.
*/
struct PxDebugTriangle
{
PxDebugTriangle(const PxVec3& p0, const PxVec3& p1, const PxVec3& p2, const PxU32& c)
: pos0(p0), color0(c), pos1(p1), color1(c), pos2(p2), color2(c) {}
PxVec3 pos0;
PxU32 color0;
PxVec3 pos1;
PxU32 color1;
PxVec3 pos2;
PxU32 color2;
};
/**
\brief Used to store a text for debug rendering. Doesn't own 'string' array.
*/
struct PxDebugText
{
PxDebugText() : string(0) {}
PxDebugText(const PxVec3& p, const PxReal& s, const PxU32& c, const char* str)
: position(p), size(s), color(c), string(str) {}
PxVec3 position;
PxReal size;
PxU32 color;
const char* string;
};
/**
\brief Interface for points, lines, triangles, and text buffer.
*/
class PxRenderBuffer
{
public:
virtual ~PxRenderBuffer() {}
virtual PxU32 getNbPoints() const = 0;
virtual const PxDebugPoint* getPoints() const = 0;
virtual PxU32 getNbLines() const = 0;
virtual const PxDebugLine* getLines() const = 0;
virtual PxU32 getNbTriangles() const = 0;
virtual const PxDebugTriangle* getTriangles() const = 0;
virtual PxU32 getNbTexts() const = 0;
virtual const PxDebugText* getTexts() const = 0;
virtual void append(const PxRenderBuffer& other) = 0;
virtual void clear() = 0;
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,406 @@
//
// 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-2018 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_COMMON_NX_SERIAL_FRAMEWORK
#define PX_PHYSICS_COMMON_NX_SERIAL_FRAMEWORK
/** \addtogroup common
@{
*/
#include "common/PxPhysXCommonConfig.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
typedef PxU16 PxType;
class PxBase;
class PxSerializationContext;
class PxRepXSerializer;
class PxSerializer;
class PxPhysics;
//! Default serialization alignment
#define PX_SERIAL_ALIGN 16
//! Serialized input data must be aligned to this value
#define PX_SERIAL_FILE_ALIGN 128
//! PxSerialObjectId value for objects that do not have an ID
#define PX_SERIAL_OBJECT_ID_INVALID 0
//! ID type for PxBase objects in a PxCollection
typedef PxU64 PxSerialObjectId;
//! Bit to mark pointer type references, @see PxDeserializationContext
#define PX_SERIAL_REF_KIND_PTR_TYPE_BIT (1u<<31)
//! Reference kind value for PxBase objects
#define PX_SERIAL_REF_KIND_PXBASE (0 | PX_SERIAL_REF_KIND_PTR_TYPE_BIT)
//! Reference kind value for material indices
#define PX_SERIAL_REF_KIND_MATERIAL_IDX (1)
//! Used to fix multi-byte characters warning from gcc for situations like: PxU32 foo = 'CCTS';
#define PX_MAKE_FOURCC(a, b, c, d) ( (a) | ((b)<<8) | ((c)<<16) | ((d)<<24) )
/**
\brief Callback class used to process PxBase objects.
@see PxSerializer::requires
*/
class PxProcessPxBaseCallback
{
public:
virtual ~PxProcessPxBaseCallback() {}
virtual void process(PxBase&) = 0;
};
/**
\brief Binary serialization context class.
This class is used to register reference values and write object
and object extra data during serialization.
It is mainly used by the serialization framework. Except for custom
serializable types, users should not have to worry about it.
@see PxDeserializationContext
*/
class PxSerializationContext
{
public:
/**
\brief Registers a reference value corresponding to a PxBase object.
This method is assumed to be called in the implementation of PxSerializer::registerReferences for serialized
references that need to be resolved on deserialization.
A reference needs to be associated with exactly one PxBase object in either the collection or the
external references collection.
Different kinds of references are supported and need to be specified. In the most common case
(PX_SERIAL_REF_KIND_PXBASE) the PxBase object matches the reference value (which is the pointer
to the PxBase object). Integer references maybe registered as well (used for internal material
indices with PX_SERIAL_REF_KIND_MATERIAL_IDX). Other kinds could be added with the restriction that
for pointer types the kind value needs to be marked with the PX_SERIAL_REF_KIND_PTR_TYPE_BIT.
\param[in] base PxBase object associated with the reference
\param[in] kind What kind of reference this is (PX_SERIAL_REF_KIND_PXBASE, PX_SERIAL_REF_KIND_MATERIAL_IDX or custom kind)
\param[in] reference Value of reference
@see PxDeserializationContext::resolveReference, PX_SERIAL_REF_KIND_PXBASE, PX_SERIAL_REF_KIND_MATERIAL_IDX, PxSerializer::registerReferences
*/
virtual void registerReference(PxBase& base, PxU32 kind, size_t reference) = 0;
/**
\brief Returns the collection that is being serialized.
*/
virtual const PxCollection& getCollection() const = 0;
/**
\brief Serializes object data and object extra data.
This function is assumed to be called within the implementation of PxSerializer::exportData and PxSerializer::exportExtraData.
@see PxSerializer::exportData, PxSerializer::exportExtraData, PxSerializer::createObject, PxDeserializationContext::readExtraData
*/
virtual void writeData(const void* data, PxU32 size) = 0;
/**
\brief Aligns the serialized data.
This function is assumed to be called within the implementation of PxSerializer::exportData and PxSerializer::exportExtraData.
@see PxSerializer::exportData, PxSerializer::exportExtraData, PxDeserializationContext::alignExtraData
*/
virtual void alignData(PxU32 alignment = PX_SERIAL_ALIGN) = 0;
/**
\brief Helper function to write a name to the extraData if serialization is configured to save names.
This function is assumed to be called within the implementation of PxSerializer::exportExtraData.
@see PxSerialization::serializeCollectionToBinary, PxDeserializationContext::readName
*/
virtual void writeName(const char* name) = 0;
protected:
PxSerializationContext() {}
virtual ~PxSerializationContext() {}
};
/**
\brief Binary deserialization context class.
This class is used to resolve references and access extra data during deserialization.
It is mainly used by the serialization framework. Except for custom
serializable types, users should not have to worry about it.
@see PxSerializationContext
*/
class PxDeserializationContext
{
public:
/**
\brief Retrieves a pointer to a deserialized PxBase object given a corresponding deserialized reference value
This method is assumed to be called in the implementation of PxSerializer::createObject in order
to update reference values on deserialization.
To update a PxBase reference the corresponding deserialized pointer value needs to be provided in order to retrieve
the location of the corresponding deserialized PxBase object. (PxDeserializationContext::translatePxBase simplifies
this common case).
For other kinds of references the reverence values need to be updated by deduction given the corresponding PxBase instance.
\param[in] kind What kind of reference this is (PX_SERIAL_REF_KIND_PXBASE, PX_SERIAL_REF_KIND_MATERIAL_IDX or custom kind)
\param[in] reference Deserialized reference value
\return PxBase object associated with the reference value
@see PxSerializationContext::registerReference, PX_SERIAL_REF_KIND_PXBASE, PX_SERIAL_REF_KIND_MATERIAL_IDX, translatePxBase
*/
virtual PxBase* resolveReference(PxU32 kind, size_t reference) const = 0;
/**
\brief Helper function to update PxBase pointer on deserialization
@see resolveReference, PX_SERIAL_REF_KIND_PXBASE
*/
template<typename T>
void translatePxBase(T*& base) { if (base) { base = static_cast<T*>(resolveReference(PX_SERIAL_REF_KIND_PXBASE, size_t(base))); } }
/**
\brief Helper function to read a name from the extra data during deserialization.
This function is assumed to be called within the implementation of PxSerializer::createObject.
@see PxSerializationContext::writeName
*/
PX_INLINE void readName(const char*& name)
{
PxU32 len = *reinterpret_cast<PxU32*>(mExtraDataAddress);
mExtraDataAddress += sizeof(len);
name = len ? reinterpret_cast<const char*>(mExtraDataAddress) : NULL;
mExtraDataAddress += len;
}
/**
\brief Function to read extra data during deserialization.
This function is assumed to be called within the implementation of PxSerializer::createObject.
@see PxSerializationContext::writeData, PxSerializer::createObject
*/
template<typename T>
PX_INLINE T* readExtraData(PxU32 count=1)
{
T* data = reinterpret_cast<T*>(mExtraDataAddress);
mExtraDataAddress += sizeof(T)*count;
return data;
}
/**
\brief Function to read extra data during deserialization optionally aligning the extra data stream before reading.
This function is assumed to be called within the implementation of PxSerializer::createObject.
@see PxSerializationContext::writeData, PxDeserializationContext::alignExtraData, PxSerializer::createObject
*/
template<typename T, PxU32 alignment>
PX_INLINE T* readExtraData(PxU32 count=1)
{
alignExtraData(alignment);
return readExtraData<T>(count);
}
/**
\brief Function to align the extra data stream to a power of 2 alignment
This function is assumed to be called within the implementation of PxSerializer::createObject.
@see PxSerializationContext::alignData, PxSerializer::createObject
*/
PX_INLINE void alignExtraData(PxU32 alignment = PX_SERIAL_ALIGN)
{
size_t addr = reinterpret_cast<size_t>(mExtraDataAddress);
addr = (addr+alignment-1)&~size_t(alignment-1);
mExtraDataAddress = reinterpret_cast<PxU8*>(addr);
}
/**
\brief Function to return the PX_PHYSX_VERSION value with which the data was originally serialized
*/
virtual PxU32 getPhysXVersion() const = 0;
protected:
PxDeserializationContext() {}
virtual ~PxDeserializationContext() {}
PxU8* mExtraDataAddress;
};
/**
\brief Callback type for exporting binary meta data for a serializable type.
@see PxSerializationRegistry::registerBinaryMetaDataCallback
\param stream Stream to store binary meta data.
*/
typedef void (*PxBinaryMetaDataCallback)(PxOutputStream& stream);
/**
\brief Class serving as a registry for XML (RepX) and binary serializable types.
In order to serialize and deserialize objects the application needs
to maintain an instance of this class. It can be created with
PxSerialization::createSerializationRegistry() and released with
PxSerializationRegistry::release().
@see PxSerialization::createSerializationRegistry
*/
class PxSerializationRegistry
{
public:
/************************************************************************************************/
/** @name Binary Serialization Functionality
*/
//@{
/**
\brief Register a serializer for a concrete type
\param type PxConcreteType corresponding to the serializer
\param serializer The PxSerializer to be registered
@see PxConcreteType, PxSerializer, PxSerializationRegistry::unregisterSerializer
*/
virtual void registerSerializer(PxType type, PxSerializer& serializer) = 0;
/**
\brief Unregister a serializer for a concrete type, and retrieves the corresponding serializer object.
\param type PxConcreteType for which the serializer should be unregistered
\return Unregistered serializer corresponding to type, NULL for types for which no serializer has been registered.
@see PxConcreteType, PxSerializationRegistry::registerSerializer, PxSerializationRegistry::release
*/
virtual PxSerializer* unregisterSerializer(PxType type) = 0;
/**
\brief Register binary meta data callback
The callback is executed when calling PxSerialization::dumpBinaryMetaData.
\param callback PxBinaryMetaDataCallback to be registered.
@see PxBinaryMetaDataCallback, PxSerialization::dumpBinaryMetaData
*/
virtual void registerBinaryMetaDataCallback(PxBinaryMetaDataCallback callback) = 0;
/**
\brief Returns PxSerializer corresponding to type
\param type PxConcreteType of the serializer requested.
\return Registered PxSerializer object corresponding to type
@see PxConcreteType
*/
virtual const PxSerializer* getSerializer(PxType type) const = 0;
//@}
/************************************************************************************************/
/** @name RepX (XML) Serialization Functionality
*/
//@{
/**
\brief Register a RepX serializer for a concrete type
\param type PxConcreteType corresponding to the RepX serializer
\param serializer The PxRepXSerializer to be registered
@see PxConcreteType, PxRepXSerializer
*/
virtual void registerRepXSerializer(PxType type, PxRepXSerializer& serializer) = 0;
/**
\brief Unregister a RepX serializer for a concrete type, and retrieves the corresponding serializer object.
\param type PxConcreteType for which the RepX serializer should be unregistered
\return Unregistered PxRepxSerializer corresponding to type, NULL for types for which no RepX serializer has been registered.
@see PxConcreteType, PxSerializationRegistry::registerRepXSerializer, PxSerializationRegistry::release
*/
virtual PxRepXSerializer* unregisterRepXSerializer(PxType type) = 0;
/**
\brief Returns RepX serializer given the corresponding type name
\param typeName Name of the type
\return Registered PxRepXSerializer object corresponding to type name
@see PxRepXSerializer, PxTypeInfo, PX_DEFINE_TYPEINFO
*/
virtual PxRepXSerializer* getRepXSerializer(const char* typeName) const = 0;
//@}
/************************************************************************************************/
/**
\brief Releases PxSerializationRegistry instance.
This unregisters all PhysX and PhysXExtension serializers. Make sure to unregister all custom type
serializers before releasing the PxSerializationRegistry.
@see PxSerializationRegistry::unregisterSerializer, PxSerializationRegistry::unregisterRepXSerializer
*/
virtual void release() = 0;
protected:
virtual ~PxSerializationRegistry(){}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,257 @@
//
// 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-2018 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_SERIALIZER_H
#define PX_SERIALIZER_H
/** \addtogroup extensions
@{
*/
#include "PxSerialFramework.h"
#include "PxCollection.h"
#include "foundation/PxAssert.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Serialization interface class.
PxSerializer is used to extend serializable PxBase classes with serialization functionality. The
interface is structured such that per-class adapter instances can be used as opposed to per-object
adapter instances, avoiding per object allocations. Hence the methods take a reference to PxBase as a parameter.
The PxSerializer interface needs to be implemented for binary or RepX serialization to work on custom
types. If only RepX serialization is needed, some methods can be left empty, as they are only needed
for binary serialization.
A default implementation is available as a template adapter (PxSerializerDefaultAdapter).
@see PxSerializerDefaultAdapter, PX_NEW_SERIALIZER_ADAPTER, PxSerializationRegistry::registerSerializer
*/
class PxSerializer
{
public:
/**********************************************************************************************************************/
/** @name Basics needed for Binary- and RepX-Serialization
*/
//@{
/**
\brief Returns string name of dynamic type.
\return Class name of most derived type of this object.
*/
virtual const char* getConcreteTypeName() const = 0;
/**
\brief Adds required objects to the collection.
This method does not add the required objects recursively, e.g. objects required by required objects.
@see PxCollection, PxSerialization::complete
*/
virtual void requiresObjects(PxBase&, PxProcessPxBaseCallback&) const = 0;
/**
\brief Whether the object is subordinate.
A class is subordinate, if it can only be instantiated in the context of another class.
\return Whether the class is subordinate
@see PxSerialization::isSerializable
*/
virtual bool isSubordinate() const = 0;
//@}
/**********************************************************************************************************************/
/**********************************************************************************************************************/
/** @name Functionality needed for Binary Serialization only
*/
//@{
/**
\brief Exports object's extra data to stream.
*/
virtual void exportExtraData(PxBase&, PxSerializationContext&) const = 0;
/**
\brief Exports object's data to stream.
*/
virtual void exportData(PxBase&, PxSerializationContext&) const = 0;
/**
\brief Register references that the object maintains to other objects.
*/
virtual void registerReferences(PxBase& obj, PxSerializationContext& s) const = 0;
/**
\brief Returns size needed to create the class instance.
\return sizeof class instance.
*/
virtual size_t getClassSize() const = 0;
/**
\brief Create object at a given address, resolve references and import extra data.
\param address Location at which object is created. Address is increased by the size of the created object.
\param context Context for reading external data and resolving references.
\return Created PxBase pointer (needs to be identical to address before increment).
*/
virtual PxBase* createObject(PxU8*& address, PxDeserializationContext& context) const = 0;
//@}
/**********************************************************************************************************************/
virtual ~PxSerializer() {}
};
/**
\brief Default PxSerializer implementation.
*/
template<class T>
class PxSerializerDefaultAdapter : public PxSerializer
{
public:
/************************************************************************************************/
/** @name Basics needed for Binary- and RepX-Serialization
*/
//@{
PxSerializerDefaultAdapter(const char* name) : mTypeName(name){}
virtual const char* getConcreteTypeName() const
{
return mTypeName;
}
virtual void requiresObjects(PxBase& obj, PxProcessPxBaseCallback& c) const
{
T& t = static_cast<T&>(obj);
t.requiresObjects(c);
}
virtual bool isSubordinate() const
{
return false;
}
//@}
/************************************************************************************************/
/** @name Functionality needed for Binary Serialization only
*/
//@{
// object methods
virtual void exportExtraData(PxBase& obj, PxSerializationContext& s) const
{
T& t = static_cast<T&>(obj);
t.exportExtraData(s);
}
virtual void exportData(PxBase& obj, PxSerializationContext& s) const
{
s.writeData(&obj, sizeof(T));
}
virtual void registerReferences(PxBase& obj, PxSerializationContext& s) const
{
T& t = static_cast<T&>(obj);
s.registerReference(obj, PX_SERIAL_REF_KIND_PXBASE, size_t(&obj));
struct RequiresCallback : public PxProcessPxBaseCallback
{
RequiresCallback(PxSerializationContext& c) : context(c) {}
RequiresCallback& operator=(RequiresCallback&) { PX_ASSERT(0); return *this; }
void process(physx::PxBase& base)
{
context.registerReference(base, PX_SERIAL_REF_KIND_PXBASE, size_t(&base));
}
PxSerializationContext& context;
};
RequiresCallback callback(s);
t.requiresObjects(callback);
}
// class methods
virtual size_t getClassSize() const
{
return sizeof(T);
}
virtual PxBase* createObject(PxU8*& address, PxDeserializationContext& context) const
{
return T::createObject(address, context);
}
//@}
/************************************************************************************************/
private:
const char* mTypeName;
};
/**
\brief Preprocessor Macro to simplify adapter creation.
Note: that the allocator used for creation needs to match with the one used in PX_DELETE_SERIALIZER_ADAPTER.
*/
#define PX_NEW_SERIALIZER_ADAPTER(x) \
*new( PxGetFoundation().getAllocatorCallback().allocate(sizeof(PxSerializerDefaultAdapter<x>), \
"PxSerializerDefaultAdapter", __FILE__, __LINE__ )) PxSerializerDefaultAdapter<x>(#x)
/**
\brief Preprocessor Macro to simplify adapter deletion.
*/
#define PX_DELETE_SERIALIZER_ADAPTER(x) \
{ PxSerializer* s = x; if (s) { s->~PxSerializer(); PxGetFoundation().getAllocatorCallback().deallocate(s); } }
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,73 @@
//
// 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-2018 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_STRING_TABLE_H
#define PX_STRING_TABLE_H
#include "foundation/PxPreprocessor.h"
/** \addtogroup physics
@{
*/
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
* \brief a table to manage strings. Strings allocated through this object are expected to be owned by this object.
*/
class PxStringTable
{
protected:
virtual ~PxStringTable(){}
public:
/**
* \brief Allocate a new string.
*
* \param[in] inSrc Source string, null terminated or null.
*
* \return *Always* a valid null terminated string. "" is returned if "" or null is passed in.
*/
virtual const char* allocateStr( const char* inSrc ) = 0;
/**
* Release the string table and all the strings associated with it.
*/
virtual void release() = 0;
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,108 @@
//
// 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-2018 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_SCALE_H
#define PX_SCALE_H
/** \addtogroup common
@{
*/
#include "common/PxPhysXCommonConfig.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxPhysics;
/**
\brief Class to define the scale at which simulation runs. Most simulation tolerances are
calculated in terms of the values here.
\note if you change the simulation scale, you will probablly also wish to change the scene's
default value of gravity, and stable simulation will probably require changes to the scene's
bounceThreshold also.
*/
class PxTolerancesScale
{
public:
/** brief
The approximate size of objects in the simulation.
For simulating roughly human-sized in metric units, 1 is a good choice.
If simulation is done in centimetres, use 100 instead. This is used to
estimate certain length-related tolerances.
*/
PxReal length;
/** brief
The typical magnitude of velocities of objects in simulation. This is used to estimate
whether a contact should be treated as bouncing or resting based on its impact velocity,
and a kinetic energy threshold below which the simulation may put objects to sleep.
For normal physical environments, a good choice is the approximate speed of an object falling
under gravity for one second.
*/
PxReal speed;
/**
\brief constructor sets to default
*/
PX_INLINE PxTolerancesScale();
/**
\brief Returns true if the descriptor is valid.
\return true if the current settings are valid (returns always true).
*/
PX_INLINE bool isValid() const;
};
PX_INLINE PxTolerancesScale::PxTolerancesScale():
length(1.0f),
speed(10.0f)
{
}
PX_INLINE bool PxTolerancesScale::isValid() const
{
return length>0.0f;
}
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,124 @@
//
// 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-2018 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_COMMON_PX_TYPEINFO
#define PX_PHYSICS_COMMON_PX_TYPEINFO
/** \addtogroup common
@{
*/
#include "common/PxPhysXCommonConfig.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief an enumeration of concrete classes inheriting from PxBase
Enumeration space is reserved for future PhysX core types, PhysXExtensions,
PhysXVehicle and Custom application types.
@see PxBase, PxTypeInfo
*/
struct PxConcreteType
{
enum Enum
{
eUNDEFINED,
eHEIGHTFIELD,
eCONVEX_MESH,
eTRIANGLE_MESH_BVH33,
eTRIANGLE_MESH_BVH34,
eRIGID_DYNAMIC,
eRIGID_STATIC,
eSHAPE,
eMATERIAL,
eCONSTRAINT,
eAGGREGATE,
eARTICULATION,
eARTICULATION_LINK,
eARTICULATION_JOINT,
ePRUNING_STRUCTURE,
eBVH_STRUCTURE,
ePHYSX_CORE_COUNT,
eFIRST_PHYSX_EXTENSION = 256,
eFIRST_VEHICLE_EXTENSION = 512,
eFIRST_USER_EXTENSION = 1024
};
};
/**
\brief a structure containing per-type information for types inheriting from PxBase
@see PxBase, PxConcreteType
*/
template<typename T> struct PxTypeInfo {};
#define PX_DEFINE_TYPEINFO(_name, _fastType) \
class _name; \
template <> struct PxTypeInfo<_name> { static const char* name() { return #_name; } enum { eFastTypeId = _fastType }; };
/* the semantics of the fastType are as follows: an object A can be cast to a type B if B's fastType is defined, and A has the same fastType.
* This implies that B has no concrete subclasses or superclasses.
*/
PX_DEFINE_TYPEINFO(PxBase, PxConcreteType::eUNDEFINED)
PX_DEFINE_TYPEINFO(PxMaterial, PxConcreteType::eMATERIAL)
PX_DEFINE_TYPEINFO(PxConvexMesh, PxConcreteType::eCONVEX_MESH)
PX_DEFINE_TYPEINFO(PxTriangleMesh, PxConcreteType::eUNDEFINED)
PX_DEFINE_TYPEINFO(PxBVH33TriangleMesh, PxConcreteType::eTRIANGLE_MESH_BVH33)
PX_DEFINE_TYPEINFO(PxBVH34TriangleMesh, PxConcreteType::eTRIANGLE_MESH_BVH34)
PX_DEFINE_TYPEINFO(PxHeightField, PxConcreteType::eHEIGHTFIELD)
PX_DEFINE_TYPEINFO(PxActor, PxConcreteType::eUNDEFINED)
PX_DEFINE_TYPEINFO(PxRigidActor, PxConcreteType::eUNDEFINED)
PX_DEFINE_TYPEINFO(PxRigidBody, PxConcreteType::eUNDEFINED)
PX_DEFINE_TYPEINFO(PxRigidDynamic, PxConcreteType::eRIGID_DYNAMIC)
PX_DEFINE_TYPEINFO(PxRigidStatic, PxConcreteType::eRIGID_STATIC)
PX_DEFINE_TYPEINFO(PxArticulationLink, PxConcreteType::eARTICULATION_LINK)
PX_DEFINE_TYPEINFO(PxArticulationJoint, PxConcreteType::eARTICULATION_JOINT)
PX_DEFINE_TYPEINFO(PxArticulation, PxConcreteType::eARTICULATION)
PX_DEFINE_TYPEINFO(PxAggregate, PxConcreteType::eAGGREGATE)
PX_DEFINE_TYPEINFO(PxConstraint, PxConcreteType::eCONSTRAINT)
PX_DEFINE_TYPEINFO(PxShape, PxConcreteType::eSHAPE)
PX_DEFINE_TYPEINFO(PxPruningStructure, PxConcreteType::ePRUNING_STRUCTURE)
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,102 @@
//
// 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-2018 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_DELAY_LOAD_HOOK
#define PX_PHYSICS_DELAY_LOAD_HOOK
#include "foundation/PxPreprocessor.h"
#include "common/PxPhysXCommonConfig.h"
/** \addtogroup foundation
@{
*/
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief PxDelayLoadHook
This is a helper class for delay loading the PhysXCommon dll and PhysXFoundation dll.
If a PhysXCommon dll or PhysXFoundation dll with a non-default file name needs to be loaded,
PxDelayLoadHook can be sub-classed to provide the custom filenames.
Once the names are set, the instance must be set for use by PhysX.dll using PxSetPhysXDelayLoadHook(),
PhysXCooking.dll using PxSetPhysXCookingDelayLoadHook() or by PhysXCommon.dll using PxSetPhysXCommonDelayLoadHook().
@see PxSetPhysXDelayLoadHook(), PxSetPhysXCookingDelayLoadHook(), PxSetPhysXCommonDelayLoadHook()
*/
class PxDelayLoadHook
{
public:
PxDelayLoadHook() {}
virtual ~PxDelayLoadHook() {}
virtual const char* getPhysXFoundationDllName() const = 0;
virtual const char* getPhysXCommonDllName() const = 0;
protected:
private:
};
/**
\brief Sets delay load hook instance for PhysX dll.
\param[in] hook Delay load hook.
@see PxDelayLoadHook
*/
PX_C_EXPORT PX_PHYSX_CORE_API void PX_CALL_CONV PxSetPhysXDelayLoadHook(const physx::PxDelayLoadHook* hook);
/**
\brief Sets delay load hook instance for PhysXCooking dll.
\param[in] hook Delay load hook.
@see PxDelayLoadHook
*/
PX_C_EXPORT PX_PHYSX_CORE_API void PX_CALL_CONV PxSetPhysXCookingDelayLoadHook(const physx::PxDelayLoadHook* hook);
/**
\brief Sets delay load hook instance for PhysXCommon dll.
\param[in] hook Delay load hook.
@see PxDelayLoadHook
*/
PX_C_EXPORT PX_PHYSX_COMMON_API void PX_CALL_CONV PxSetPhysXCommonDelayLoadHook(const physx::PxDelayLoadHook* hook);
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,110 @@
//
// 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-2018 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_BVH_33_MIDPHASE_DESC_H
#define PX_BVH_33_MIDPHASE_DESC_H
/** \addtogroup cooking
@{
*/
#include "foundation/PxPreprocessor.h"
#include "foundation/PxSimpleTypes.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/** \brief Enumeration for mesh cooking hints. */
struct PxMeshCookingHint
{
enum Enum
{
eSIM_PERFORMANCE = 0, //!< Default value. Favors higher quality hierarchy with higher runtime performance over cooking speed.
eCOOKING_PERFORMANCE = 1 //!< Enables fast cooking path at the expense of somewhat lower quality hierarchy construction.
};
};
/**
\brief Structure describing parameters affecting BVH33 midphase mesh structure.
@see PxCookingParams, PxMidphaseDesc
*/
struct PxBVH33MidphaseDesc
{
/**
\brief Controls the trade-off between mesh size and runtime performance.
Using a value of 1.0 will produce a larger cooked mesh with generally higher runtime performance,
using 0.0 will produce a smaller cooked mesh, with generally lower runtime performance.
Values outside of [0,1] range will be clamped and cause a warning when any mesh gets cooked.
<b>Default value:</b> 0.55
<b>Range:</b> [0.0f, 1.0f]
*/
PxF32 meshSizePerformanceTradeOff;
/**
\brief Mesh cooking hint. Used to specify mesh hierarchy construction preference.
<b>Default value:</b> PxMeshCookingHint::eSIM_PERFORMANCE
*/
PxMeshCookingHint::Enum meshCookingHint;
/**
\brief Desc initialization to default value.
*/
void setToDefault()
{
meshSizePerformanceTradeOff = 0.55f;
meshCookingHint = PxMeshCookingHint::eSIM_PERFORMANCE;
}
/**
\brief Returns true if the descriptor is valid.
\return true if the current settings are valid.
*/
bool isValid() const
{
if(meshSizePerformanceTradeOff < 0.0f || meshSizePerformanceTradeOff > 1.0f)
return false;
return true;
}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif // PX_BVH_33_MIDPHASE_DESC_H

View File

@ -0,0 +1,90 @@
//
// 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-2018 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_BVH_34_MIDPHASE_DESC_H
#define PX_BVH_34_MIDPHASE_DESC_H
/** \addtogroup cooking
@{
*/
#include "foundation/PxPreprocessor.h"
#include "foundation/PxSimpleTypes.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Structure describing parameters affecting BVH34 midphase mesh structure.
@see PxCookingParams, PxMidphaseDesc
*/
struct PxBVH34MidphaseDesc
{
/**
\brief Mesh cooking hint for max primitives per leaf limit.
Less primitives per leaf produces larger meshes with better runtime performance
and worse cooking performance. More triangles per leaf results in faster cooking speed and
smaller mesh sizes, but with worse runtime performance.
<b>Default value:</b> 4
<b>Range:</b> <4, 15>
*/
PxU32 numPrimsPerLeaf;
/**
\brief Desc initialization to default value.
*/
void setToDefault()
{
numPrimsPerLeaf = 4;
}
/**
\brief Returns true if the descriptor is valid.
\return true if the current settings are valid.
*/
bool isValid() const
{
if(numPrimsPerLeaf < 4 || numPrimsPerLeaf > 15)
return false;
return true;
}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif // PX_BVH_34_MIDPHASE_DESC_H

View File

@ -0,0 +1,109 @@
//
// 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-2018 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_BVH_STRUCTURE_DESC_H
#define PX_BVH_STRUCTURE_DESC_H
/** \addtogroup cooking
@{
*/
#include "common/PxCoreUtilityTypes.h"
#include "common/PxPhysXCommonConfig.h"
#include "foundation/PxTransform.h"
#include "foundation/PxBounds3.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Descriptor class for #PxBVHStructure.
@see PxBVHStructure
*/
class PxBVHStructureDesc
{
public:
PX_INLINE PxBVHStructureDesc();
/**
\brief Pointer to first bounding box.
*/
PxBoundedData bounds;
/**
\brief Initialize the BVH structure descriptor
*/
PX_INLINE void setToDefault();
/**
\brief Returns true if the descriptor is valid.
\return true if the current settings are valid.
*/
PX_INLINE bool isValid() const;
protected:
};
PX_INLINE PxBVHStructureDesc::PxBVHStructureDesc()
{
}
PX_INLINE void PxBVHStructureDesc::setToDefault()
{
*this = PxBVHStructureDesc();
}
PX_INLINE bool PxBVHStructureDesc::isValid() const
{
// Check BVH desc data
if(!bounds.data)
return false;
if(bounds.stride < sizeof(PxBounds3)) //should be at least one point's worth of data
return false;
if(bounds.count == 0)
return false;
return true;
}
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif // PX_BVH_STRUCTURE_DESC_H

View File

@ -0,0 +1,307 @@
//
// 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-2018 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_COLLISION_NXCONVEXMESHDESC
#define PX_COLLISION_NXCONVEXMESHDESC
/** \addtogroup cooking
@{
*/
#include "foundation/PxVec3.h"
#include "foundation/PxFlags.h"
#include "common/PxCoreUtilityTypes.h"
#include "geometry/PxConvexMesh.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Flags which describe the format and behavior of a convex mesh.
*/
struct PxConvexFlag
{
enum Enum
{
/**
Denotes the use of 16-bit vertex indices in PxConvexMeshDesc::triangles or PxConvexMeshDesc::polygons.
(otherwise, 32-bit indices are assumed)
@see #PxConvexMeshDesc.indices
*/
e16_BIT_INDICES = (1<<0),
/**
Automatically recomputes the hull from the vertices. If this flag is not set, you must provide the entire geometry manually.
\note There are two different algorithms for hull computation, please see PxConvexMeshCookingType.
@see PxConvexMeshCookingType
*/
eCOMPUTE_CONVEX = (1<<1),
/**
\brief Checks and removes almost zero-area triangles during convex hull computation.
The rejected area size is specified in PxCookingParams::areaTestEpsilon
\note This flag is only used in combination with eCOMPUTE_CONVEX.
@see PxCookingParams PxCookingParams::areaTestEpsilon
*/
eCHECK_ZERO_AREA_TRIANGLES = (1<<2),
/**
\brief Quantizes the input vertices using the k-means clustering
\note The input vertices are quantized to PxConvexMeshDesc::quantizedCount
see http://en.wikipedia.org/wiki/K-means_clustering
*/
eQUANTIZE_INPUT = (1 << 3),
/**
\brief Disables the convex mesh validation to speed-up hull creation. Please use separate validation
function in checked/debug builds. Creating a convex mesh with invalid input data without prior validation
may result in undefined behavior.
@see PxCooking::validateConvexMesh
*/
eDISABLE_MESH_VALIDATION = (1 << 4),
/**
\brief Enables plane shifting vertex limit algorithm.
Plane shifting is an alternative algorithm for the case when the computed hull has more vertices
than the specified vertex limit.
The default algorithm computes the full hull, and an OBB around the input vertices. This OBB is then sliced
with the hull planes until the vertex limit is reached.The default algorithm requires the vertex limit
to be set to at least 8, and typically produces results that are much better quality than are produced
by plane shifting.
When plane shifting is enabled, the hull computation stops when vertex limit is reached. The hull planes
are then shifted to contain all input vertices, and the new plane intersection points are then used to
generate the final hull with the given vertex limit.Plane shifting may produce sharp edges to vertices
very far away from the input cloud, and does not guarantee that all input vertices are inside the resulting
hull.However, it can be used with a vertex limit as low as 4.
*/
ePLANE_SHIFTING = (1 << 5),
/**
\brief Inertia tensor computation is faster using SIMD code, but the precision is lower, which may result
in incorrect inertia for very thin hulls.
*/
eFAST_INERTIA_COMPUTATION = (1 << 6),
/**
\brief Convex hulls are created with respect to GPU simulation limitations. Vertex limit is set to 64 and
vertex limit per face is internally set to 32.
\note Can be used only with eCOMPUTE_CONVEX flag.
*/
eGPU_COMPATIBLE = (1 << 7),
/**
\brief Convex hull input vertices are shifted to be around origin to provide better computation stability.
It is recommended to provide input vertices around the origin, otherwise use this flag to improve
numerical stability.
\note Is used only with eCOMPUTE_CONVEX flag.
*/
eSHIFT_VERTICES = (1 << 8)
};
};
/**
\brief collection of set bits defined in PxConvexFlag.
@see PxConvexFlag
*/
typedef PxFlags<PxConvexFlag::Enum,PxU16> PxConvexFlags;
PX_FLAGS_OPERATORS(PxConvexFlag::Enum,PxU16)
/**
\brief Descriptor class for #PxConvexMesh.
\note The number of vertices and the number of convex polygons in a cooked convex mesh is limited to 256.
@see PxConvexMesh PxConvexMeshGeometry PxShape PxPhysics.createConvexMesh()
*/
class PxConvexMeshDesc
{
public:
/**
\brief Vertex positions data in PxBoundedData format.
<b>Default:</b> NULL
*/
PxBoundedData points;
/**
\brief Polygons data in PxBoundedData format.
<p>Pointer to first polygon. </p>
<b>Default:</b> NULL
@see PxHullPolygon
*/
PxBoundedData polygons;
/**
\brief Polygon indices data in PxBoundedData format.
<p>Pointer to first index.</p>
<b>Default:</b> NULL
<p>This is declared as a void pointer because it is actually either an PxU16 or a PxU32 pointer.</p>
@see PxHullPolygon PxConvexFlag::e16_BIT_INDICES
*/
PxBoundedData indices;
/**
\brief Flags bits, combined from values of the enum ::PxConvexFlag
<b>Default:</b> 0
*/
PxConvexFlags flags;
/**
\brief Limits the number of vertices of the result convex mesh. Hard maximum limit is 256
and minimum limit is 4 if PxConvexFlag::ePLANE_SHIFTING is used, otherwise the minimum
limit is 8.
\note Vertex limit is only used when PxConvexFlag::eCOMPUTE_CONVEX is specified.
\note The please see PxConvexFlag::ePLANE_SHIFTING for algorithm explanation
@see PxConvexFlag::ePLANE_SHIFTING
<b>Range:</b> [4, 255]<br>
<b>Default:</b> 255
*/
PxU16 vertexLimit;
/**
\brief Maximum number of vertices after quantization. The quantization is done during the vertex cleaning phase.
The quantization is applied when PxConvexFlag::eQUANTIZE_INPUT is specified.
@see PxConvexFlag::eQUANTIZE_INPUT
<b>Range:</b> [4, 65535]<br>
<b>Default:</b> 255
*/
PxU16 quantizedCount;
/**
\brief constructor sets to default.
*/
PX_INLINE PxConvexMeshDesc();
/**
\brief (re)sets the structure to the default.
*/
PX_INLINE void setToDefault();
/**
\brief Returns true if the descriptor is valid.
\return True if the current settings are valid
*/
PX_INLINE bool isValid() const;
};
PX_INLINE PxConvexMeshDesc::PxConvexMeshDesc() //constructor sets to default
: vertexLimit(255), quantizedCount(255)
{
}
PX_INLINE void PxConvexMeshDesc::setToDefault()
{
*this = PxConvexMeshDesc();
}
PX_INLINE bool PxConvexMeshDesc::isValid() const
{
// Check geometry
if(points.count < 3 || //at least 1 trig's worth of points
(points.count > 0xffff && flags & PxConvexFlag::e16_BIT_INDICES))
return false;
if(!points.data)
return false;
if(points.stride < sizeof(PxVec3)) //should be at least one point's worth of data
return false;
if (quantizedCount < 4)
return false;
// Check topology
if(polygons.data)
{
if(polygons.count < 4) // we require 2 neighbors for each vertex - 4 polygons at least
return false;
if(!indices.data) // indices must be provided together with polygons
return false;
PxU32 limit = (flags & PxConvexFlag::e16_BIT_INDICES) ? sizeof(PxU16) : sizeof(PxU32);
if(indices.stride < limit)
return false;
limit = sizeof(PxHullPolygon);
if(polygons.stride < limit)
return false;
}
else
{
// We can compute the hull from the vertices
if(!(flags & PxConvexFlag::eCOMPUTE_CONVEX))
return false; // If the mesh is convex and we're not allowed to compute the hull,
// you have to provide it completely (geometry & topology).
}
if((flags & PxConvexFlag::ePLANE_SHIFTING) && vertexLimit < 4)
{
return false;
}
if (!(flags & PxConvexFlag::ePLANE_SHIFTING) && vertexLimit < 8)
{
return false;
}
if(vertexLimit > 256)
{
return false;
}
return true;
}
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,563 @@
//
// 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-2018 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_COOKING_H
#define PX_COOKING_H
/** \addtogroup cooking
@{
*/
#include "common/PxPhysXCommonConfig.h"
#include "common/PxTolerancesScale.h"
#include "cooking/Pxc.h"
#include "cooking/PxConvexMeshDesc.h"
#include "cooking/PxTriangleMeshDesc.h"
#include "cooking/PxMidphaseDesc.h"
#include "cooking/PxBVHStructureDesc.h"
#include "geometry/PxTriangleMesh.h"
#include "geometry/PxBVHStructure.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxPhysicsInsertionCallback;
class PxFoundation;
/**
\brief Result from convex cooking.
*/
struct PxConvexMeshCookingResult
{
enum Enum
{
/**
\brief Convex mesh cooking succeeded.
*/
eSUCCESS,
/**
\brief Convex mesh cooking failed, algorithm couldn't find 4 initial vertices without a small triangle.
@see PxCookingParams::areaTestEpsilon PxConvexFlag::eCHECK_ZERO_AREA_TRIANGLES
*/
eZERO_AREA_TEST_FAILED,
/**
\brief Convex mesh cooking succeeded, but the algorithm has reached the 255 polygons limit.
The produced hull does not contain all input vertices. Try to simplify the input vertices
or try to use the eINFLATE_CONVEX or the eQUANTIZE_INPUT flags.
@see PxConvexFlag::eINFLATE_CONVEX PxConvexFlag::eQUANTIZE_INPUT
*/
ePOLYGONS_LIMIT_REACHED,
/**
\brief Something unrecoverable happened. Check the error stream to find out what.
*/
eFAILURE
};
};
/** \brief Enumeration for convex mesh cooking algorithms. */
struct PxConvexMeshCookingType
{
enum Enum
{
/**
\brief The Quickhull algorithm constructs the hull from the given input points. The resulting hull
will only contain a subset of the input points.
*/
eQUICKHULL
};
};
/**
\brief Result from triangle mesh cooking
*/
struct PxTriangleMeshCookingResult
{
enum Enum
{
/**
\brief Everything is A-OK.
*/
eSUCCESS = 0,
/**
\brief a triangle is too large for well-conditioned results. Tessellate the mesh for better behavior, see the user guide section on cooking for more details.
*/
eLARGE_TRIANGLE,
/**
\brief Something unrecoverable happened. Check the error stream to find out what.
*/
eFAILURE
};
};
/**
\brief Enum for the set of mesh pre-processing parameters.
*/
struct PxMeshPreprocessingFlag
{
enum Enum
{
/**
\brief When set, mesh welding is performed. See PxCookingParams::meshWeldTolerance. Clean mesh must be enabled.
*/
eWELD_VERTICES = 1 << 0,
/**
\brief When set, mesh cleaning is disabled. This makes cooking faster.
When clean mesh is not performed, mesh welding is also not performed.
It is recommended to use only meshes that passed during validateTriangleMesh.
*/
eDISABLE_CLEAN_MESH = 1 << 1,
/**
\brief When set, active edges are set for each triangle edge. This makes cooking faster but slow up contact generation.
*/
eDISABLE_ACTIVE_EDGES_PRECOMPUTE = 1 << 2,
/**
\brief When set, 32-bit indices will always be created regardless of triangle count.
\note By default mesh will be created with 16-bit indices for triangle count <= 0xFFFF and 32-bit otherwise.
*/
eFORCE_32BIT_INDICES = 1 << 3
};
};
typedef PxFlags<PxMeshPreprocessingFlag::Enum,PxU32> PxMeshPreprocessingFlags;
/**
\brief Structure describing parameters affecting mesh cooking.
@see PxSetCookingParams() PxGetCookingParams()
*/
struct PxCookingParams
{
/**
\brief Zero-size area epsilon used in convex hull computation.
If the area of a triangle of the hull is below this value, the triangle will be rejected. This test
is done only if PxConvexFlag::eCHECK_ZERO_AREA_TRIANGLES is used.
@see PxConvexFlag::eCHECK_ZERO_AREA_TRIANGLES
<b>Default value:</b> 0.06f*PxTolerancesScale.length*PxTolerancesScale.length
<b>Range:</b> (0.0f, PX_MAX_F32)
*/
float areaTestEpsilon;
/**
\brief Plane tolerance used in convex hull computation.
The value is used during hull construction. When a new point is about to be added to the hull it
gets dropped when the point is closer to the hull than the planeTolerance. The planeTolerance
is increased according to the hull size.
If 0.0f is set all points are accepted when the convex hull is created. This may lead to edge cases
where the new points may be merged into an existing polygon and the polygons plane equation might
slightly change therefore. This might lead to failures during polygon merging phase in the hull computation.
It is recommended to use the default value, however if it is required that all points needs to be
accepted or huge thin convexes are created, it might be required to lower the default value.
\note The plane tolerance is used only within PxConvexMeshCookingType::eQUICKHULL algorithm.
<b>Default value:</b> 0.0007f
<b>Range:</b> <0.0f, PX_MAX_F32)
*/
float planeTolerance;
/**
\brief Convex hull creation algorithm.
<b>Default value:</b> PxConvexMeshCookingType::eQUICKHULL
@see PxConvexMeshCookingType
*/
PxConvexMeshCookingType::Enum convexMeshCookingType;
/**
\brief When true, the face remap table is not created. This saves a significant amount of memory, but the SDK will
not be able to provide the remap information for internal mesh triangles returned by collisions,
sweeps or raycasts hits.
<b>Default value:</b> false
*/
bool suppressTriangleMeshRemapTable;
/**
\brief When true, the triangle adjacency information is created. You can get the adjacency triangles
for a given triangle from getTriangle.
<b>Default value:</b> false
*/
bool buildTriangleAdjacencies;
/**
\brief When true, addigional information required for GPU-accelerated rigid body simulation is created. This can increase memory usage and cooking times for convex meshes and triangle meshes.
<b>Default value:</b> false
*/
bool buildGPUData;
/**
\brief Tolerance scale is used to check if cooked triangles are not too huge. This check will help with simulation stability.
\note The PxTolerancesScale values have to match the values used when creating a PxPhysics or PxScene instance.
@see PxTolerancesScale
*/
PxTolerancesScale scale;
/**
\brief Mesh pre-processing parameters. Used to control options like whether the mesh cooking performs vertex welding before cooking.
<b>Default value:</b> 0
*/
PxMeshPreprocessingFlags meshPreprocessParams;
/**
\brief Mesh weld tolerance. If mesh welding is enabled, this controls the distance at which vertices are welded.
If mesh welding is not enabled, this value defines the acceptance distance for mesh validation. Provided no two vertices are within this distance, the mesh is considered to be
clean. If not, a warning will be emitted. Having a clean, welded mesh is required to achieve the best possible performance.
The default vertex welding uses a snap-to-grid approach. This approach effectively truncates each vertex to integer values using meshWeldTolerance.
Once these snapped vertices are produced, all vertices that snap to a given vertex on the grid are remapped to reference a single vertex. Following this,
all triangles' indices are remapped to reference this subset of clean vertices. It should be noted that the vertices that we do not alter the
position of the vertices; the snap-to-grid is only performed to identify nearby vertices.
The mesh validation approach also uses the same snap-to-grid approach to identify nearby vertices. If more than one vertex snaps to a given grid coordinate,
we ensure that the distance between the vertices is at least meshWeldTolerance. If this is not the case, a warning is emitted.
<b>Default value:</b> 0.0
*/
PxReal meshWeldTolerance;
/**
\brief Controls the desired midphase desc structure for triangle meshes.
@see PxBVH33MidphaseDesc, PxBVH34MidphaseDesc, PxMidphaseDesc
<b>Default value:</b> PxMeshMidPhase::eBVH33
*/
PxMidphaseDesc midphaseDesc;
/**
\brief Vertex limit beyond which additional acceleration structures are computed for each convex mesh. Increase that limit to reduce memory usage.
Computing the extra structures all the time does not guarantee optimal performance. There is a per-platform break-even point below which the
extra structures actually hurt performance.
<b>Default value:</b> 32
*/
PxU32 gaussMapLimit;
PxCookingParams(const PxTolerancesScale& sc):
areaTestEpsilon (0.06f*sc.length*sc.length),
planeTolerance (0.0007f),
convexMeshCookingType (PxConvexMeshCookingType::eQUICKHULL),
suppressTriangleMeshRemapTable (false),
buildTriangleAdjacencies (false),
buildGPUData (false),
scale (sc),
meshPreprocessParams (0),
meshWeldTolerance (0.f),
gaussMapLimit (32)
{
}
};
class PxCooking
{
public:
/**
\brief Closes this instance of the interface.
This function should be called to cleanly shut down the Cooking library before application exit.
\note This function is required to be called to release foundation usage.
*/
virtual void release() = 0;
/**
\brief Sets cooking parameters
\param[in] params Cooking parameters
@see getParams()
*/
virtual void setParams(const PxCookingParams& params) = 0;
/**
\brief Gets cooking parameters
\return Current cooking parameters.
@see PxCookingParams setParams()
*/
virtual const PxCookingParams& getParams() const = 0;
/**
\brief Checks endianness is the same between cooking & target platforms
\return True if there is and endian mismatch.
*/
virtual bool platformMismatch() const = 0;
/**
\brief Cooks a triangle mesh. The results are written to the stream.
To create a triangle mesh object it is necessary to first 'cook' the mesh data into
a form which allows the SDK to perform efficient collision detection.
cookTriangleMesh() allows a mesh description to be cooked into a binary stream
suitable for loading and performing collision detection at runtime.
\param[in] desc The triangle mesh descriptor to read the mesh from.
\param[in] stream User stream to output the cooked data.
\param[out] condition Result from triangle mesh cooking.
\return true on success
@see cookConvexMesh() setParams() PxPhysics.createTriangleMesh() PxTriangleMeshCookingResult::Enum
*/
virtual bool cookTriangleMesh(const PxTriangleMeshDesc& desc, PxOutputStream& stream, PxTriangleMeshCookingResult::Enum* condition = NULL) const = 0;
/**
\brief Cooks and creates a triangle mesh and inserts it into PxPhysics.
\note PxPhysicsInsertionCallback can be obtained through PxPhysics::getPhysicsInsertionCallback().
\param[in] desc The triangle mesh descriptor to read the mesh from.
\param[in] insertionCallback The insertion interface from PxPhysics.
\param[out] condition Result from triangle mesh cooking.
\return PxTriangleMesh pointer on success.
@see cookTriangleMesh() setParams() PxPhysics.createTriangleMesh() PxPhysicsInsertionCallback
*/
virtual PxTriangleMesh* createTriangleMesh(const PxTriangleMeshDesc& desc, PxPhysicsInsertionCallback& insertionCallback, PxTriangleMeshCookingResult::Enum* condition = NULL) const = 0;
/**
\brief Verifies if the triangle mesh is valid. Prints an error message for each inconsistency found.
The following conditions are true for a valid triangle mesh:
1. There are no duplicate vertices (within specified vertexWeldTolerance. See PxCookingParams::meshWeldTolerance)
2. There are no large triangles (within specified PxTolerancesScale.)
\param[in] desc The triangle mesh descriptor to read the mesh from.
\return true if all the validity conditions hold, false otherwise.
@see cookTriangleMesh()
*/
virtual bool validateTriangleMesh(const PxTriangleMeshDesc& desc) const = 0;
/**
\brief Cooks a convex mesh. The results are written to the stream.
To create a triangle mesh object it is necessary to first 'cook' the mesh data into
a form which allows the SDK to perform efficient collision detection.
cookConvexMesh() allows a mesh description to be cooked into a binary stream
suitable for loading and performing collision detection at runtime.
\note The number of vertices and the number of convex polygons in a cooked convex mesh is limited to 255.
\note If those limits are exceeded in either the user-provided data or the final cooked mesh, an error is reported.
\param[in] desc The convex mesh descriptor to read the mesh from.
\param[in] stream User stream to output the cooked data.
\param[out] condition Result from convex mesh cooking.
\return true on success.
@see cookTriangleMesh() setParams() PxConvexMeshCookingResult::Enum
*/
virtual bool cookConvexMesh(const PxConvexMeshDesc& desc, PxOutputStream& stream, PxConvexMeshCookingResult::Enum* condition = NULL) const = 0;
/**
\brief Cooks and creates a convex mesh and inserts it into PxPhysics.
\note This method does the same as cookConvexMesh, but the produced convex mesh is not stored
into a stream but is directly inserted in PxPhysics. Use this method if you are unable to cook offline.
\note PxPhysicsInsertionCallback can be obtained through PxPhysics::getPhysicsInsertionCallback().
\param[in] desc The convex mesh descriptor to read the mesh from.
\param[in] insertionCallback The insertion interface from PxPhysics.
\param[out] condition Result from convex mesh cooking.
\return PxConvexMesh pointer on success
@see cookConvexMesh() setParams() PxPhysicsInsertionCallback
*/
virtual PxConvexMesh* createConvexMesh(const PxConvexMeshDesc& desc, PxPhysicsInsertionCallback& insertionCallback, PxConvexMeshCookingResult::Enum* condition = NULL) const = 0;
/**
\brief Verifies if the convex mesh is valid. Prints an error message for each inconsistency found.
The convex mesh descriptor must contain an already created convex mesh - the vertices, indices and polygons must be provided.
\note This function should be used if PxConvexFlag::eDISABLE_MESH_VALIDATION is planned to be used in release builds.
\param[in] desc The convex mesh descriptor to read the mesh from.
\return true if all the validity conditions hold, false otherwise.
@see cookConvexMesh()
*/
virtual bool validateConvexMesh(const PxConvexMeshDesc& desc) const = 0;
/**
\brief Computed hull polygons from given vertices and triangles. Polygons are needed for PxConvexMeshDesc rather than triangles.
Please note that the resulting polygons may have different number of vertices. Some vertices may be removed.
The output vertices, indices and polygons must be used to construct a hull.
The provided PxAllocatorCallback does allocate the out array's. It is the user responsibility to deallocated those
array's.
\param[in] mesh Simple triangle mesh containing vertices and triangles used to compute polygons.
\param[in] inCallback Memory allocator for out array allocations.
\param[out] nbVerts Number of vertices used by polygons.
\param[out] vertices Vertices array used by polygons.
\param[out] nbIndices Number of indices used by polygons.
\param[out] indices Indices array used by polygons.
\param[out] nbPolygons Number of created polygons.
\param[out] hullPolygons Polygons array.
\return true on success
@see cookConvexMesh() PxConvexFlags PxConvexMeshDesc PxSimpleTriangleMesh
*/
virtual bool computeHullPolygons(const PxSimpleTriangleMesh& mesh, PxAllocatorCallback& inCallback, PxU32& nbVerts, PxVec3*& vertices,
PxU32& nbIndices, PxU32*& indices, PxU32& nbPolygons, PxHullPolygon*& hullPolygons) const = 0;
/**
\brief Cooks a heightfield. The results are written to the stream.
To create a heightfield object there is an option to precompute some of calculations done while loading the heightfield data.
cookHeightField() allows a heightfield description to be cooked into a binary stream
suitable for loading and performing collision detection at runtime.
\param[in] desc The heightfield descriptor to read the HF from.
\param[in] stream User stream to output the cooked data.
\return true on success
@see PxPhysics.createHeightField()
*/
virtual bool cookHeightField(const PxHeightFieldDesc& desc, PxOutputStream& stream) const = 0;
/**
\brief Cooks and creates a heightfield mesh and inserts it into PxPhysics.
\param[in] desc The heightfield descriptor to read the HF from.
\param[in] insertionCallback The insertion interface from PxPhysics.
\return PxHeightField pointer on success
@see cookConvexMesh() setParams() PxPhysics.createTriangleMesh() PxPhysicsInsertionCallback
*/
virtual PxHeightField* createHeightField(const PxHeightFieldDesc& desc, PxPhysicsInsertionCallback& insertionCallback) const = 0;
/**
\brief Cooks a bounding volume hierarchy structure. The results are written to the stream.
cookBVHStructure() allows a BVH structure description to be cooked into a binary stream
suitable for loading and performing BVH detection at runtime.
\param[in] desc The BVH structure descriptor.
\param[in] stream User stream to output the cooked data.
\return true on success.
@see PxBVHStructure PxRigidActorExt::getRigidActorShapeLocalBoundsList
*/
virtual bool cookBVHStructure(const PxBVHStructureDesc& desc, PxOutputStream& stream) const = 0;
/**
\brief Cooks and creates a bounding volume hierarchy structure and inserts it into PxPhysics.
\note This method does the same as cookBVHStructure, but the produced BVH structure is not stored
into a stream but is directly inserted in PxPhysics. Use this method if you are unable to cook offline.
\note PxPhysicsInsertionCallback can be obtained through PxPhysics::getPhysicsInsertionCallback().
\param[in] desc The BVH structure descriptor.
\param[in] insertionCallback The insertion interface from PxPhysics.
\return PxBVHStructure pointer on success
@see cookBVHStructure() PxPhysicsInsertionCallback
*/
virtual PxBVHStructure* createBVHStructure(const PxBVHStructureDesc& desc, PxPhysicsInsertionCallback& insertionCallback) const = 0;
protected:
virtual ~PxCooking(){}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/**
\brief Create an instance of the cooking interface.
Note that the foundation object is handled as an application-wide singleton in statically linked executables
and a DLL-wide singleton in dynamically linked executables. Therefore, if you are using the runtime SDK in the
same executable as cooking, you should pass the Physics's copy of foundation (acquired with
PxPhysics::getFoundation()) to the cooker. This will also ensure correct handling of memory for objects
passed from the cooker to the SDK.
To use cooking in standalone mode, create an instance of the Foundation object with PxCreateCookingFoundation.
You should pass the same foundation object to all instances of the cooking interface.
\param[in] version the SDK version number
\param[in] foundation the foundation object associated with this instance of the cooking interface.
\param[in] params the parameters for this instance of the cooking interface
\return true on success.
*/
PX_C_EXPORT PX_PHYSX_COOKING_API physx::PxCooking* PX_CALL_CONV PxCreateCooking(physx::PxU32 version,
physx::PxFoundation& foundation,
const physx::PxCookingParams& params);
/** @} */
#endif

View File

@ -0,0 +1,119 @@
//
// 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-2018 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_MIDPHASE_DESC_H
#define PX_MIDPHASE_DESC_H
/** \addtogroup cooking
@{
*/
#include "geometry/PxTriangleMesh.h"
#include "cooking/PxBVH33MidphaseDesc.h"
#include "cooking/PxBVH34MidphaseDesc.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Structure describing parameters affecting midphase mesh structure.
@see PxCookingParams, PxBVH33MidphaseDesc, PxBVH34MidphaseDesc
*/
class PxMidphaseDesc
{
public:
PX_FORCE_INLINE PxMidphaseDesc() { setToDefault(PxMeshMidPhase::eBVH33); }
/**
\brief Returns type of midphase mesh structure.
\return PxMeshMidPhase::Enum
@see PxMeshMidPhase::Enum
*/
PX_FORCE_INLINE PxMeshMidPhase::Enum getType() const { return mType; }
/**
\brief Midphase descriptors union
@see PxBV33MidphaseDesc, PxBV34MidphaseDesc
*/
union {
PxBVH33MidphaseDesc mBVH33Desc;
PxBVH34MidphaseDesc mBVH34Desc;
};
/**
\brief Initialize the midphase mesh structure descriptor
\param[in] type Midphase mesh structure descriptor
@see PxBV33MidphaseDesc, PxBV34MidphaseDesc
*/
void setToDefault(PxMeshMidPhase::Enum type)
{
mType = type;
if(type==PxMeshMidPhase::eBVH33)
mBVH33Desc.setToDefault();
else if(type==PxMeshMidPhase::eBVH34)
mBVH34Desc.setToDefault();
}
/**
\brief Returns true if the descriptor is valid.
\return true if the current settings are valid.
*/
bool isValid() const
{
if(mType==PxMeshMidPhase::eBVH33)
return mBVH33Desc.isValid();
else if(mType==PxMeshMidPhase::eBVH34)
return mBVH34Desc.isValid();
return false;
}
PX_FORCE_INLINE PxMidphaseDesc& operator=(PxMeshMidPhase::Enum descType)
{
setToDefault(descType);
return *this;
}
protected:
PxMeshMidPhase::Enum mType;
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif // PX_MIDPHASE_DESC_UNION_H

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-2018 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_COLLISION_NXTRIANGLEMESHDESC
#define PX_COLLISION_NXTRIANGLEMESHDESC
/** \addtogroup cooking
@{
*/
#include "PxPhysXConfig.h"
#include "geometry/PxSimpleTriangleMesh.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Descriptor class for #PxTriangleMesh.
Note that this class is derived from PxSimpleTriangleMesh which contains the members that describe the basic mesh.
The mesh data is *copied* when an PxTriangleMesh object is created from this descriptor. After the call the
user may discard the triangle data.
@see PxTriangleMesh PxTriangleMeshGeometry PxShape
*/
class PxTriangleMeshDesc : public PxSimpleTriangleMesh
{
public:
/**
Optional pointer to first material index, or NULL. There are PxSimpleTriangleMesh::numTriangles indices in total.
Caller may add materialIndexStride bytes to the pointer to access the next triangle.
When a triangle mesh collides with another object, a material is required at the collision point.
If materialIndices is NULL, then the material of the PxShape instance is used.
Otherwise, if the point of contact is on a triangle with index i, then the material index is determined as:
PxMaterialTableIndex index = *(PxMaterialTableIndex *)(((PxU8*)materialIndices) + materialIndexStride * i);
If the contact point falls on a vertex or an edge, a triangle adjacent to the vertex or edge is selected, and its index
used to look up a material. The selection is arbitrary but consistent over time.
<b>Default:</b> NULL
@see materialIndexStride
*/
PxTypedStridedData<PxMaterialTableIndex> materialIndices;
/**
\brief Constructor sets to default.
*/
PX_INLINE PxTriangleMeshDesc();
/**
\brief (re)sets the structure to the default.
*/
PX_INLINE void setToDefault();
/**
\brief Returns true if the descriptor is valid.
\return true if the current settings are valid
*/
PX_INLINE bool isValid() const;
};
PX_INLINE PxTriangleMeshDesc::PxTriangleMeshDesc() //constructor sets to default
{
PxSimpleTriangleMesh::setToDefault();
}
PX_INLINE void PxTriangleMeshDesc::setToDefault()
{
*this = PxTriangleMeshDesc();
}
PX_INLINE bool PxTriangleMeshDesc::isValid() const
{
if(points.count < 3) //at least 1 trig's worth of points
return false;
if ((!triangles.data) && (points.count%3)) // Non-indexed mesh => we must ensure the geometry defines an implicit number of triangles // i.e. numVertices can't be divided by 3
return false;
//add more validity checks here
if (materialIndices.data && materialIndices.stride < sizeof(PxMaterialTableIndex))
return false;
return PxSimpleTriangleMesh::isValid();
}
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,57 @@
//
// 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-2018 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_COOKING_NX
#define PX_COOKING_NX
#include "foundation/Px.h"
// define API function declaration
#if !defined PX_PHYSX_STATIC_LIB
#if PX_WINDOWS
#if defined PX_PHYSX_COOKING_EXPORTS
#define PX_PHYSX_COOKING_API __declspec(dllexport)
#else
#define PX_PHYSX_COOKING_API __declspec(dllimport)
#endif
#elif PX_UNIX_FAMILY
#define PX_PHYSX_COOKING_API PX_UNIX_EXPORT
#endif
#endif
#if !defined(PX_PHYSX_COOKING_API)
#define PX_PHYSX_COOKING_API
#endif
#ifndef PX_C_EXPORT
#define PX_C_EXPORT extern "C"
#endif
#endif

View File

@ -0,0 +1,425 @@
//
// 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-2018 NVIDIA Corporation. All rights reserved.
#ifndef PXCUDACONTEXTMANAGER_PXCUDACONTEXTMANAGER_H
#define PXCUDACONTEXTMANAGER_PXCUDACONTEXTMANAGER_H
#include "foundation/PxPreprocessor.h"
#if PX_SUPPORT_GPU_PHYSX
#include "foundation/PxSimpleTypes.h"
#include "foundation/PxErrorCallback.h"
#include "foundation/PxFlags.h"
#include "task/PxTaskDefine.h"
#include "cudamanager/PxCudaMemoryManager.h"
/* Forward decl to avoid inclusion of cuda.h */
typedef struct CUctx_st *CUcontext;
typedef struct CUgraphicsResource_st *CUgraphicsResource;
typedef int CUdevice;
namespace physx
{
class PxGpuDispatcher;
/** \brief Possible graphic/CUDA interoperability modes for context */
struct PxCudaInteropMode
{
/**
* \brief Possible graphic/CUDA interoperability modes for context
*/
enum Enum
{
NO_INTEROP = 0,
D3D10_INTEROP,
D3D11_INTEROP,
OGL_INTEROP,
COUNT
};
};
struct PxCudaInteropRegisterFlag
{
enum Enum
{
eNONE = 0x00,
eREAD_ONLY = 0x01,
eWRITE_DISCARD = 0x02,
eSURFACE_LDST = 0x04,
eTEXTURE_GATHER = 0x08
};
};
/**
\brief collection of set bits defined in NxCudaInteropRegisterFlag.
@see NxCudaInteropRegisterFlag
*/
typedef PxFlags<PxCudaInteropRegisterFlag::Enum, uint32_t> PxCudaInteropRegisterFlags;
PX_FLAGS_OPERATORS(PxCudaInteropRegisterFlag::Enum, uint32_t)
//! \brief Descriptor used to create a PxCudaContextManager
class PxCudaContextManagerDesc
{
public:
/**
* \brief The CUDA context to manage
*
* If left NULL, the PxCudaContextManager will create a new context. If
* graphicsDevice is also not NULL, this new CUDA context will be bound to
* that graphics device, enabling the use of CUDA/Graphics interop features.
*
* If ctx is not NULL, the specified context must be applied to the thread
* that is allocating the PxCudaContextManager at creation time (aka, it
* cannot be popped). The PxCudaContextManager will take ownership of the
* context until the manager is released. All access to the context must be
* gated by lock acquisition.
*
* If the user provides a context for the PxCudaContextManager, the context
* _must_ have either been created on the GPU ordinal returned by
* PxGetSuggestedCudaDeviceOrdinal() or on your graphics device.
*
* It is perfectly acceptable to allocate device or host pinned memory from
* the context outside the scope of the PxCudaMemoryManager, so long as you
* manage its eventual cleanup.
*/
CUcontext *ctx;
/**
* \brief D3D device pointer or OpenGl context handle
*
* Only applicable when ctx is NULL, thus forcing a new context to be
* created. In that case, the created context will be bound to this
* graphics device.
*/
void *graphicsDevice;
#if PX_SUPPORT_GPU_PHYSX
/**
* \brief Application-specific GUID
*
* If your application employs PhysX modules that use CUDA you need to use a GUID
* so that patches for new architectures can be released for your game.You can obtain a GUID for your
* application from Nvidia.
*/
const char* appGUID;
#endif
/**
* \brief The CUDA/Graphics interop mode of this context
*
* If ctx is NULL, this value describes the nature of the graphicsDevice
* pointer provided by the user. Else it describes the nature of the
* context provided by the user.
*/
PxCudaInteropMode::Enum interopMode;
/**
* \brief Size of persistent memory
*
* This memory is allocated up front and stays allocated until the
* PxCudaContextManager is released. Size is in bytes, has to be power of two
* and bigger than the page size. Set to 0 to only use dynamic pages.
*
* Note: On Vista O/S and above, there is a per-memory allocation overhead
* to every CUDA work submission, so we recommend that you carefully tune
* this initial base memory size to closely approximate the amount of
* memory your application will consume.
Note: This is currently not used by PxSceneFlag::eENABLE_GPU_DYNAMICS. Memory allocation properties are configured
for GPU rigid bodies using PxSceneDesc::gpuDynamicsConfig.
*/
uint32_t memoryBaseSize[PxCudaBufferMemorySpace::COUNT];
/**
* \brief Size of memory pages
*
* The memory manager will dynamically grow and shrink in blocks multiple of
* this page size. Size has to be power of two and bigger than 0.
Note: This is currently not used by PxSceneFlag::eENABLE_GPU_DYNAMICS. Memory allocation properties are configured
for GPU rigid bodies using PxSceneDesc::gpuDynamicsConfig.
*/
uint32_t memoryPageSize[PxCudaBufferMemorySpace::COUNT];
/**
* \brief Maximum size of memory that the memory manager will allocate
Note: This is currently not used by PxSceneFlag::eENABLE_GPU_DYNAMICS. Memory allocation properties are configured
for GPU rigid bodies using PxSceneDesc::gpuDynamicsConfig.
*/
uint32_t maxMemorySize[PxCudaBufferMemorySpace::COUNT];
PX_INLINE PxCudaContextManagerDesc()
{
ctx = NULL;
interopMode = PxCudaInteropMode::NO_INTEROP;
graphicsDevice = 0;
#if PX_SUPPORT_GPU_PHYSX
appGUID = NULL;
#endif
for(uint32_t i = 0; i < PxCudaBufferMemorySpace::COUNT; i++)
{
memoryBaseSize[i] = 0;
memoryPageSize[i] = 2 * 1024*1024;
maxMemorySize[i] = UINT32_MAX;
}
}
};
/**
* \brief Manages memory, thread locks, and task scheduling for a CUDA context
*
* A PxCudaContextManager manages access to a single CUDA context, allowing it to
* be shared between multiple scenes. Memory allocations are dynamic: starting
* with an initial heap size and growing on demand by a configurable page size.
* The context must be acquired from the manager before using any CUDA APIs.
*
* The PxCudaContextManager is based on the CUDA driver API and explictly does not
* support the CUDA runtime API (aka, CUDART).
*
* To enable CUDA use by an APEX scene, a PxCudaContextManager must be created
* (supplying your own CUDA context, or allowing a new context to be allocated
* for you), the PxGpuDispatcher for that context is retrieved via the
* getGpuDispatcher() method, and this is assigned to the TaskManager that is
* given to the scene via its NxApexSceneDesc.
*/
class PxCudaContextManager
{
public:
/**
* \brief Acquire the CUDA context for the current thread
*
* Acquisitions are allowed to be recursive within a single thread.
* You can acquire the context multiple times so long as you release
* it the same count.
*
* The context must be acquired before using most CUDA functions.
*
* It is not necessary to acquire the CUDA context inside GpuTask
* launch functions, because the PxGpuDispatcher will have already
* acquired the context for its worker thread. However it is not
* harmfull to (re)acquire the context in code that is shared between
* GpuTasks and non-task functions.
*/
virtual void acquireContext() = 0;
/**
* \brief Release the CUDA context from the current thread
*
* The CUDA context should be released as soon as practically
* possible, to allow other CPU threads (including the
* PxGpuDispatcher) to work efficiently.
*/
virtual void releaseContext() = 0;
/**
* \brief Return the CUcontext
*/
virtual CUcontext getContext() = 0;
/**
* \brief Return the PxCudaMemoryManager instance associated with this
* CUDA context
* Note: This is currently not used by PxSceneFlag::eENABLE_GPU_DYNAMICS. Memory allocation properties are configured
* for GPU rigid bodies using PxSceneDesc::gpuDynamicsConfig.
*/
virtual PxCudaMemoryManager *getMemoryManager() = 0;
/**
* \brief Return the PxGpuDispatcher instance associated with this
* CUDA context
*/
virtual class physx::PxGpuDispatcher *getGpuDispatcher() = 0;
/**
* \brief Context manager has a valid CUDA context
*
* This method should be called after creating a PxCudaContextManager,
* especially if the manager was responsible for allocating its own
* CUDA context (desc.ctx == NULL). If it returns false, there is
* no point in assigning this manager's PxGpuDispatcher to a
* TaskManager as it will be unable to execute GpuTasks.
*/
virtual bool contextIsValid() const = 0;
/* Query CUDA context and device properties, without acquiring context */
virtual bool supportsArchSM10() const = 0; //!< G80
virtual bool supportsArchSM11() const = 0; //!< G92
virtual bool supportsArchSM12() const = 0; //!< GT200
virtual bool supportsArchSM13() const = 0; //!< GT260
virtual bool supportsArchSM20() const = 0; //!< GF100
virtual bool supportsArchSM30() const = 0; //!< GK100
virtual bool supportsArchSM35() const = 0; //!< GK110
virtual bool supportsArchSM50() const = 0; //!< GM100
virtual bool supportsArchSM52() const = 0; //!< GM200
virtual bool supportsArchSM60() const = 0; //!< GP100
virtual bool isIntegrated() const = 0; //!< true if GPU is an integrated (MCP) part
virtual bool canMapHostMemory() const = 0; //!< true if GPU map host memory to GPU (0-copy)
virtual int getDriverVersion() const = 0; //!< returns cached value of cuGetDriverVersion()
virtual size_t getDeviceTotalMemBytes() const = 0; //!< returns cached value of device memory size
virtual int getMultiprocessorCount() const = 0; //!< returns cache value of SM unit count
virtual unsigned int getClockRate() const = 0; //!< returns cached value of SM clock frequency
virtual int getSharedMemPerBlock() const = 0; //!< returns total amount of shared memory available per block in bytes
virtual int getSharedMemPerMultiprocessor() const = 0; //!< returns total amount of shared memory available per multiprocessor in bytes
virtual unsigned int getMaxThreadsPerBlock() const = 0; //!< returns the maximum number of threads per block
virtual const char *getDeviceName() const = 0; //!< returns device name retrieved from driver
virtual CUdevice getDevice() const = 0; //!< returns device handle retrieved from driver
virtual PxCudaInteropMode::Enum getInteropMode() const = 0; //!< interop mode the context was created with
virtual void setUsingConcurrentStreams(bool) = 0; //!< turn on/off using concurrent streams for GPU work
virtual bool getUsingConcurrentStreams() const = 0; //!< true if GPU work can run in concurrent streams
/* End query methods that don't require context to be acquired */
/**
* \brief Register a rendering resource with CUDA
*
* This function is called to register render resources (allocated
* from OpenGL) with CUDA so that the memory may be shared
* between the two systems. This is only required for render
* resources that are designed for interop use. In APEX, each
* render resource descriptor that could support interop has a
* 'registerInCUDA' boolean variable.
*
* The function must be called again any time your graphics device
* is reset, to re-register the resource.
*
* Returns true if the registration succeeded. A registered
* resource must be unregistered before it can be released.
*
* \param resource [OUT] the handle to the resource that can be used with CUDA
* \param buffer [IN] GLuint buffer index to be mapped to cuda
* \param flags [IN] cuda interop registration flags
*/
virtual bool registerResourceInCudaGL(CUgraphicsResource &resource, uint32_t buffer, PxCudaInteropRegisterFlags flags = PxCudaInteropRegisterFlags()) = 0;
/**
* \brief Register a rendering resource with CUDA
*
* This function is called to register render resources (allocated
* from Direct3D) with CUDA so that the memory may be shared
* between the two systems. This is only required for render
* resources that are designed for interop use. In APEX, each
* render resource descriptor that could support interop has a
* 'registerInCUDA' boolean variable.
*
* The function must be called again any time your graphics device
* is reset, to re-register the resource.
*
* Returns true if the registration succeeded. A registered
* resource must be unregistered before it can be released.
*
* \param resource [OUT] the handle to the resource that can be used with CUDA
* \param resourcePointer [IN] A pointer to either IDirect3DResource9, or ID3D10Device, or ID3D11Resource to be registered.
* \param flags [IN] cuda interop registration flags
*/
virtual bool registerResourceInCudaD3D(CUgraphicsResource &resource, void *resourcePointer, PxCudaInteropRegisterFlags flags = PxCudaInteropRegisterFlags()) = 0;
/**
* \brief Unregister a rendering resource with CUDA
*
* If a render resource was successfully registered with CUDA using
* the registerResourceInCuda***() methods, this function must be called
* to unregister the resource before the it can be released.
*/
virtual bool unregisterResourceInCuda(CUgraphicsResource resource) = 0;
/**
* \brief Determine if the user has configured a dedicated PhysX GPU in the NV Control Panel
* \note If using CUDA Interop, this will always return false
* \returns 1 if there is a dedicated GPU
* 0 if there is NOT a dedicated GPU
* -1 if the routine is not implemented
*/
virtual int usingDedicatedGPU() const = 0;
/**
* \brief Release the PxCudaContextManager
*
* When the manager instance is released, it also releases its
* PxGpuDispatcher instance and PxCudaMemoryManager. Before the memory
* manager is released, it frees all allocated memory pages. If the
* PxCudaContextManager created the CUDA context it was responsible
* for, it also frees that context.
*
* Do not release the PxCudaContextManager if there are any scenes
* using its PxGpuDispatcher. Those scenes must be released first
* since there is no safe way to remove a PxGpuDispatcher from a
* TaskManager once the TaskManager has been given to a scene.
*
*/
virtual void release() = 0;
protected:
/**
* \brief protected destructor, use release() method
*/
virtual ~PxCudaContextManager() {}
};
/**
* \brief Convenience class for holding CUDA lock within a scope
*/
class PxScopedCudaLock
{
public:
/**
* \brief ScopedCudaLock constructor
*/
PxScopedCudaLock(PxCudaContextManager& ctx) : mCtx(&ctx)
{
mCtx->acquireContext();
}
/**
* \brief ScopedCudaLock destructor
*/
~PxScopedCudaLock()
{
mCtx->releaseContext();
}
protected:
/**
* \brief CUDA context manager pointer (initialized in the constructor)
*/
PxCudaContextManager* mCtx;
};
} // end physx namespace
#endif // PX_SUPPORT_GPU_PHYSX
#endif // PXCUDACONTEXTMANAGER_PXCUDACONTEXTMANAGER_H

View File

@ -0,0 +1,281 @@
//
// 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-2018 NVIDIA Corporation. All rights reserved.
#ifndef PXCUDACONTEXTMANAGER_PXCUDAMEMORYMANAGER_H
#define PXCUDACONTEXTMANAGER_PXCUDAMEMORYMANAGER_H
#include "foundation/PxPreprocessor.h"
#if PX_SUPPORT_GPU_PHYSX
#include "task/PxTaskDefine.h"
// some macros to keep the source code more readable
#define PX_ALLOC_INFO(name, ID) __FILE__, __LINE__, name, physx::PxAllocId::ID
#define PX_ALLOC_INFO_PARAMS_DECL(p0, p1, p2, p3) const char* file = p0, int line = p1, const char* allocName = p2, physx::PxAllocId::Enum allocId = physx::PxAllocId::p3
#define PX_ALLOC_INFO_PARAMS_DEF() const char* file, int line, const char* allocName, physx::PxAllocId::Enum allocId
#define PX_ALLOC_INFO_PARAMS_INPUT() file, line, allocName, allocId
#define PX_ALLOC_INFO_PARAMS_INPUT_INFO(info) info.getFileName(), info.getLine(), info.getAllocName(), info.getAllocId()
#ifndef NULL // don't want to include <string.h>
#define NULL 0
#endif
namespace physx
{
PX_PUSH_PACK_DEFAULT
/** \brief ID of the Feature which owns/allocated memory from the heap
*
* Maximum of 64k IDs allowed.
*/
struct PxAllocId
{
/**
* \brief ID of the Feature which owns/allocated memory from the heap
*/
enum Enum
{
UNASSIGNED, //!< default
APEX, //!< APEX stuff not further classified
PARTICLES, //!< all particle related
GPU_UTIL, //!< e.g. RadixSort (used in SPH and deformable self collision)
CLOTH, //!< all cloth related
NUM_IDS //!< number of IDs, be aware that ApexHeapStats contains PxAllocIdStats[NUM_IDS]
};
};
/// \brief memory type managed by a heap
struct PxCudaBufferMemorySpace
{
/**
* \brief memory type managed by a heap
*/
enum Enum
{
T_GPU,
T_PINNED_HOST,
T_WRITE_COMBINED,
T_HOST,
COUNT
};
};
/// \brief class to track allocation statistics, see PxgMirrored
class PxAllocInfo
{
public:
/**
* \brief AllocInfo default constructor
*/
PxAllocInfo() {}
/**
* \brief AllocInfo constructor that initializes all of the members
*/
PxAllocInfo(const char* file, int line, const char* allocName, PxAllocId::Enum allocId)
: mFileName(file)
, mLine(line)
, mAllocName(allocName)
, mAllocId(allocId)
{}
/// \brief get the allocation file name
inline const char* getFileName() const
{
return mFileName;
}
/// \brief get the allocation line
inline int getLine() const
{
return mLine;
}
/// \brief get the allocation name
inline const char* getAllocName() const
{
return mAllocName;
}
/// \brief get the allocation ID
inline PxAllocId::Enum getAllocId() const
{
return mAllocId;
}
private:
const char* mFileName;
int mLine;
const char* mAllocName;
PxAllocId::Enum mAllocId;
};
/// \brief statistics collected per AllocationId by HeapManager.
struct PxAllocIdStats
{
size_t size; //!< currently allocated memory by this ID
size_t maxSize; //!< max allocated memory by this ID
size_t elements; //!< number of current allocations by this ID
size_t maxElements; //!< max number of allocations by this ID
};
class PxCudaMemoryManager;
typedef size_t PxCudaBufferPtr;
/// \brief Hint flag to tell how the buffer will be used
struct PxCudaBufferFlags
{
/// \brief Enumerations for the hint flag to tell how the buffer will be used
enum Enum
{
F_READ = (1 << 0),
F_WRITE = (1 << 1),
F_READ_WRITE = F_READ | F_WRITE
};
};
/// \brief Memory statistics struct returned by CudaMemMgr::getStats()
struct PxCudaMemoryManagerStats
{
size_t heapSize; //!< Size of all pages allocated for this memory type (allocated + free).
size_t totalAllocated; //!< Size occupied by the current allocations.
size_t maxAllocated; //!< High water mark of allocations since the SDK was created.
PxAllocIdStats allocIdStats[PxAllocId::NUM_IDS]; //!< Stats for each allocation ID, see PxAllocIdStats
};
/// \brief Buffer type: made of hint flags and the memory space (Device Memory, Pinned Host Memory, ...)
struct PxCudaBufferType
{
/// \brief PxCudaBufferType copy constructor
PX_INLINE PxCudaBufferType(const PxCudaBufferType& t)
: memorySpace(t.memorySpace)
, flags(t.flags)
{}
/// \brief PxCudaBufferType constructor to explicitely assign members
PX_INLINE PxCudaBufferType(PxCudaBufferMemorySpace::Enum _memSpace, PxCudaBufferFlags::Enum _flags)
: memorySpace(_memSpace)
, flags(_flags)
{}
PxCudaBufferMemorySpace::Enum memorySpace; //!< specifies which memory space for the buffer
PxCudaBufferFlags::Enum flags; //!< specifies the usage flags for the buffer
};
/// \brief Buffer which keeps informations about allocated piece of memory.
class PxCudaBuffer
{
public:
/// Retrieves the manager over which the buffer was allocated.
virtual PxCudaMemoryManager* getCudaMemoryManager() const = 0;
/// Releases the buffer and the memory it used, returns true if successful.
virtual bool free() = 0;
/// Realloc memory. Use to shrink or resize the allocated chunk of memory of this buffer.
/// Returns true if successful. Fails if the operation would change the address and need a memcopy.
/// In that case the user has to allocate, copy and free the memory with separate steps.
/// Realloc to size 0 always returns false and doesn't change the state.
virtual bool realloc(size_t size, PX_ALLOC_INFO_PARAMS_DECL(NULL, 0, NULL, UNASSIGNED)) = 0;
/// Returns the type of the allocated memory.
virtual const PxCudaBufferType& getType() const = 0;
/// Returns the pointer to the allocated memory.
virtual PxCudaBufferPtr getPtr() const = 0;
/// Returns the size of the allocated memory.
virtual size_t getSize() const = 0;
protected:
/// \brief protected destructor
virtual ~PxCudaBuffer() {}
};
/// \brief Allocator class for different kinds of CUDA related memory.
class PxCudaMemoryManager
{
public:
/// Allocate memory of given type and size. Returns a CudaBuffer if successful. Returns NULL if failed.
virtual PxCudaBuffer* alloc(const PxCudaBufferType& type, size_t size, PX_ALLOC_INFO_PARAMS_DECL(NULL, 0, NULL, UNASSIGNED)) = 0;
/// Basic heap allocator without PxCudaBuffer
virtual PxCudaBufferPtr alloc(PxCudaBufferMemorySpace::Enum memorySpace, size_t size, PX_ALLOC_INFO_PARAMS_DECL(NULL, 0, NULL, UNASSIGNED)) = 0;
/// Basic heap deallocator without PxCudaBuffer
virtual bool free(PxCudaBufferMemorySpace::Enum memorySpace, PxCudaBufferPtr addr) = 0;
/// Basic heap realloc without PxCudaBuffer
virtual bool realloc(PxCudaBufferMemorySpace::Enum memorySpace, PxCudaBufferPtr addr, size_t size, PX_ALLOC_INFO_PARAMS_DECL(NULL, 0, NULL, UNASSIGNED)) = 0;
/// Retrieve stats for the memory of given type. See PxCudaMemoryManagerStats.
virtual void getStats(const PxCudaBufferType& type, PxCudaMemoryManagerStats& outStats) = 0;
/// Ensure that a given amount of free memory is available. Triggers CUDA allocations in size of (2^n * pageSize) if necessary.
/// Returns false if page allocations failed.
virtual bool reserve(const PxCudaBufferType& type, size_t size) = 0;
/// Set the page size. The managed memory grows by blocks 2^n * pageSize. Page allocations trigger CUDA driver allocations,
/// so the page size should be reasonably big. Returns false if input size was invalid, i.e. not power of two.
/// Default is 2 MB.
virtual bool setPageSize(const PxCudaBufferType& type, size_t size) = 0;
/// Set the upper limit until which pages of a given memory type can be allocated.
/// Reducing the max when it is already hit does not shrink the memory until it is deallocated by releasing the buffers which own the memory.
virtual bool setMaxMemorySize(const PxCudaBufferType& type, size_t size) = 0;
/// Returns the base size. The base memory block stays persistently allocated over the SDKs life time.
virtual size_t getBaseSize(const PxCudaBufferType& type) = 0;
/// Returns the currently set page size. The memory grows and shrinks in blocks of size (2^n pageSize)
virtual size_t getPageSize(const PxCudaBufferType& type) = 0;
/// Returns the upper limit until which the manager is allowed to allocate additional pages from the CUDA driver.
virtual size_t getMaxMemorySize(const PxCudaBufferType& type) = 0;
/// Get device mapped pinned host mem ptr. Operation only valid for memory space PxCudaBufferMemorySpace::T_PINNED_HOST.
virtual PxCudaBufferPtr getMappedPinnedPtr(PxCudaBufferPtr hostPtr) = 0;
protected:
/// \brief protected destructor
virtual ~PxCudaMemoryManager() {}
};
PX_POP_PACK
} // end physx namespace
#endif // PX_SUPPORT_GPU_PHYSX
#endif // PXCUDACONTEXTMANAGER_PXCUDAMEMORYMANAGER_H

View File

@ -0,0 +1,86 @@
//
// 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-2018 NVIDIA Corporation. All rights reserved.
#ifndef PXCUDACONTEXTMANAGER_PXGPUCOPYDESC_H
#define PXCUDACONTEXTMANAGER_PXGPUCOPYDESC_H
#include "foundation/PxPreprocessor.h"
#if PX_SUPPORT_GPU_PHYSX
#include "task/PxTaskDefine.h"
namespace physx
{
PX_PUSH_PACK_DEFAULT
/**
* \brief Input descriptor for the GpuDispatcher's built-in copy kernel
*
* All host memory involved in copy transactions must be page-locked.
* If more than one descriptor is passed to the copy kernel in one launch,
* the descriptors themselves must be in page-locked memory.
*/
struct PxGpuCopyDesc
{
/**
* \brief Input descriptor for the GpuDispatcher's built-in copy kernel
*/
enum CopyType
{
HostToDevice,
DeviceToHost,
DeviceToDevice,
DeviceMemset32
};
size_t dest; //!< the destination
size_t source; //!< the source (32bit value when type == DeviceMemset)
size_t bytes; //!< the size in bytes
CopyType type; //!< the memory transaction type
/**
* \brief Copy is optimally performed as 64bit words, requires 64bit alignment. But it can
* gracefully degrade to 32bit copies if necessary
*/
PX_INLINE bool isValid()
{
bool ok = true;
ok &= ((dest & 0x3) == 0);
ok &= ((type == DeviceMemset32) || (source & 0x3) == 0);
ok &= ((bytes & 0x3) == 0);
return ok;
}
};
PX_POP_PACK
} // end physx namespace
#endif // PX_SUPPORT_GPU_PHYSX
#endif // PXCUDACONTEXTMANAGER_PXGPUCOPYDESC_H

View File

@ -0,0 +1,149 @@
//
// 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-2018 NVIDIA Corporation. All rights reserved.
#ifndef PXCUDACONTEXTMANAGER_PXGPUCOPYDESCQUEUE_H
#define PXCUDACONTEXTMANAGER_PXGPUCOPYDESCQUEUE_H
#include "foundation/PxPreprocessor.h"
#if PX_SUPPORT_GPU_PHYSX
#include "foundation/PxAssert.h"
#include "task/PxTaskDefine.h"
#include "task/PxGpuDispatcher.h"
#include "cudamanager/PxGpuCopyDesc.h"
#include "cudamanager/PxCudaContextManager.h"
/* forward decl to avoid including <cuda.h> */
typedef struct CUstream_st* CUstream;
namespace physx
{
PX_PUSH_PACK_DEFAULT
/// \brief Container class for queueing PxGpuCopyDesc instances in pinned (non-pageable) CPU memory
class PxGpuCopyDescQueue
{
public:
/// \brief PxGpuCopyDescQueue constructor
PxGpuCopyDescQueue(PxGpuDispatcher& d)
: mDispatcher(d)
, mBuffer(0)
, mStream(0)
, mReserved(0)
, mOccupancy(0)
, mFlushed(0)
{
}
/// \brief PxGpuCopyDescQueue destructor
~PxGpuCopyDescQueue()
{
if (mBuffer)
{
mDispatcher.getCudaContextManager()->getMemoryManager()->free(PxCudaBufferMemorySpace::T_PINNED_HOST, (size_t) mBuffer);
}
}
/// \brief Reset the enqueued copy descriptor list
///
/// Must be called at least once before any copies are enqueued, and each time the launched
/// copies are known to have been completed. The recommended use case is to call this at the
/// start of each simulation step.
void reset(CUstream stream, uint32_t reserveSize)
{
if (reserveSize > mReserved)
{
if (mBuffer)
{
mDispatcher.getCudaContextManager()->getMemoryManager()->free(
PxCudaBufferMemorySpace::T_PINNED_HOST,
(size_t) mBuffer);
mReserved = 0;
}
mBuffer = (PxGpuCopyDesc*) mDispatcher.getCudaContextManager()->getMemoryManager()->alloc(
PxCudaBufferMemorySpace::T_PINNED_HOST,
reserveSize * sizeof(PxGpuCopyDesc),
PX_ALLOC_INFO("PxGpuCopyDescQueue", GPU_UTIL));
if (mBuffer)
{
mReserved = reserveSize;
}
}
mOccupancy = 0;
mFlushed = 0;
mStream = stream;
}
/// \brief Enqueue the specified copy descriptor, or launch immediately if no room is available
void enqueue(PxGpuCopyDesc& desc)
{
PX_ASSERT(desc.isValid());
if (desc.bytes == 0)
{
return;
}
if (mOccupancy < mReserved)
{
mBuffer[ mOccupancy++ ] = desc;
}
else
{
mDispatcher.launchCopyKernel(&desc, 1, mStream);
}
}
/// \brief Launch all copies queued since the last flush or reset
void flushEnqueued()
{
if (mOccupancy > mFlushed)
{
mDispatcher.launchCopyKernel(mBuffer + mFlushed, mOccupancy - mFlushed, mStream);
mFlushed = mOccupancy;
}
}
private:
PxGpuDispatcher& mDispatcher;
PxGpuCopyDesc* mBuffer;
CUstream mStream;
uint32_t mReserved;
uint32_t mOccupancy;
uint32_t mFlushed;
void operator=(const PxGpuCopyDescQueue&); // prevent a warning...
};
PX_POP_PACK
} // end physx namespace
#endif // PX_SUPPORT_GPU_PHYSX
#endif // PXCUDACONTEXTMANAGER_PXGPUCOPYDESCQUEUE_H

View File

@ -0,0 +1,132 @@
//
// 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-2018 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_BINARY_CONVERTER_H
#define PX_BINARY_CONVERTER_H
/** \addtogroup extensions
@{
*/
#include "common/PxPhysXCommonConfig.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
struct PxConverterReportMode
{
enum Enum
{
eNONE, //!< Silent mode. If enabled, no information is sent to the error stream.
eNORMAL, //!< Normal mode. If enabled, only important information is sent to the error stream.
eVERBOSE //!< Verbose mode. If enabled, detailed information is sent to the error stream.
};
};
/**
\brief Binary converter for serialized streams.
The binary converter class is targeted at converting binary streams from authoring platforms,
such as windows, osx or linux to any game runtime platform supported by PhysX. Particularly
it is currently not supported to run the converter on a platforms that has an endian mismatch
with the platform corresponding to the source binary file and source meta data.
If you want to use multiple threads for batch conversions, please create one instance
of this class for each thread.
@see PxSerialization.createBinaryConverter
*/
class PxBinaryConverter
{
public:
/**
\brief Releases binary converter
*/
virtual void release() = 0;
/**
\brief Sets desired report mode.
\param[in] mode Report mode
*/
virtual void setReportMode(PxConverterReportMode::Enum mode) = 0;
/**
\brief Setups source and target meta-data streams
The source meta data provided needs to have the same endianness as the platform the converter is run on.
The meta data needs to be set before calling the conversion method.
\param[in] srcMetaData Source platform's meta-data stream
\param[in] dstMetaData Target platform's meta-data stream
\return True if success
*/
virtual bool setMetaData(PxInputStream& srcMetaData, PxInputStream& dstMetaData) = 0;
/**
\brief Test utility function to compare two sets of meta data.
The meta data needs to be set before calling the compareMetaData method.
This method will issue PxErrorCode::eDEBUG_INFO messages if mismatches are encountered.
\return True if meta data is equivalend
*/
virtual bool compareMetaData() const = 0;
/**
\brief Converts binary stream from source platform to target platform
The converter needs to be configured with source and destination meta data before calling the conversion method.
The source meta data needs to correspond to the same platform as the source binary data.
\param[in] srcStream Source stream
\param[in] srcSize Number of bytes to convert
\param[in] targetStream Target stream
\return True if success
*/
virtual bool convert(PxInputStream& srcStream, PxU32 srcSize, PxOutputStream& targetStream) = 0;
protected:
PxBinaryConverter() {}
virtual ~PxBinaryConverter() {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,75 @@
//
// 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-2018 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_EXTENSIONS_BROAD_PHASE_H
#define PX_PHYSICS_EXTENSIONS_BROAD_PHASE_H
/** \addtogroup extensions
@{
*/
#include "PxPhysXConfig.h"
#include "common/PxPhysXCommonConfig.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxBroadPhaseExt
{
public:
/**
\brief Creates regions for PxSceneDesc, from a global box.
This helper simply subdivides the given global box into a 2D grid of smaller boxes. Each one of those smaller boxes
is a region of interest for the broadphase. There are nbSubdiv*nbSubdiv regions in the 2D grid. The function does not
subdivide along the given up axis.
This is the simplest setup one can use with PxBroadPhaseType::eMBP. A more sophisticated setup would try to cover
the game world with a non-uniform set of regions (i.e. not just a grid).
\param[out] regions Regions computed from the input global box
\param[in] globalBounds World-space box covering the game world
\param[in] nbSubdiv Grid subdivision level. The function will create nbSubdiv*nbSubdiv regions.
\param[in] upAxis Up axis (0 for X, 1 for Y, 2 for Z).
\return number of regions written out to the 'regions' array
@see PxSceneDesc PxBroadPhaseType
*/
static PxU32 createRegionsFromWorldBounds(PxBounds3* regions, const PxBounds3& globalBounds, PxU32 nbSubdiv, PxU32 upAxis=1);
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,119 @@
//
// 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-2018 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_COLLECTION_EXT_H
#define PX_COLLECTION_EXT_H
/** \addtogroup extensions
@{
*/
#include "PxPhysXConfig.h"
#include "common/PxCollection.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxCollectionExt
{
public:
/**
\brief Removes and releases all object from a collection.
The Collection itself is not released.
If the releaseExclusiveShapes flag is not set to true, release() will not be called on exclusive shapes.
It is assumed that the application holds a reference to each of the objects in the collection, with the exception of objects that are not releasable
(PxBase::isReleasable()). In general, objects that violate this assumption need to be removed from the collection prior to calling releaseObjects.
\note when a shape is created with PxRigidActor::createShape() or PxRigidActorExt::createExclusiveShape(), the only counted reference is held by the actor.
If such a shape and its actor are present in the collection, the reference count will be decremented once when the actor is released, and once when the
shape is released, resulting in undefined behavior. Shape reference counts can be incremented with PxShape::acquireReference().
\param[in] collection to remove and release all object from.
\param[in] releaseExclusiveShapes if this parameter is set to false, release() will not be called on exclusive shapes.
*/
static void releaseObjects(PxCollection& collection, bool releaseExclusiveShapes = true);
/**
\brief Removes objects of a given type from a collection, potentially adding them to another collection.
\param[in,out] collection Collection from which objects are removed
\param[in] concreteType PxConcreteType of sdk objects that should be removed
\param[in,out] to Optional collection to which the removed objects are added
@see PxCollection, PxConcreteType
*/
static void remove(PxCollection& collection, PxType concreteType, PxCollection* to = NULL);
/**
\brief Collects all objects in PxPhysics that are shareable across multiple scenes.
This function creates a new collection from all objects that are shareable across multiple
scenes. Instances of the following types are included: PxConvexMesh, PxTriangleMesh,
PxHeightField, PxShape and PxMaterial.
This is a helper function to ease the creation of collections for serialization.
\param[in] physics The physics SDK instance from which objects are collected. See #PxPhysics
\return Collection to which objects are added. See #PxCollection
@see PxCollection, PxPhysics
*/
static PxCollection* createCollection(PxPhysics& physics);
/**
\brief Collects all objects from a PxScene.
This function creates a new collection from all objects that where added to the specified
PxScene. Instances of the following types are included: PxActor, PxAggregate,
PxArticulation and PxJoint (other PxConstraint types are not included).
This is a helper function to ease the creation of collections for serialization.
The function PxSerialization.complete() can be used to complete the collection with required objects prior to
serialization.
\param[in] scene The PxScene instance from which objects are collected. See #PxScene
\return Collection to which objects are added. See #PxCollection
@see PxCollection, PxScene, PxSerialization.complete()
*/
static PxCollection* createCollection(PxScene& scene);
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,70 @@
//
// 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-2018 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_EXTENSIONS_CONSTRAINT_H
#define PX_PHYSICS_EXTENSIONS_CONSTRAINT_H
#include "foundation/PxPreprocessor.h"
/** \addtogroup extensions
@{
*/
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Unique identifiers for extensions classes which implement a constraint based on PxConstraint.
\note Users which want to create their own custom constraint types should choose an ID larger or equal to eNEXT_FREE_ID
and not eINVALID_ID.
@see PxConstraint PxSimulationEventCallback.onConstraintBreak()
*/
struct PxConstraintExtIDs
{
enum Enum
{
eJOINT,
eVEHICLE_SUSP_LIMIT,
eVEHICLE_STICKY_TYRE,
eNEXT_FREE_ID,
eINVALID_ID = 0x7fffffff
};
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,168 @@
//
// 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-2018 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_CONTACTJOINT_H
#define PX_CONTACTJOINT_H
#include "extensions/PxJoint.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxContactJoint;
/**
\brief Create a distance Joint.
\param[in] physics The physics SDK
\param[in] actor0 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localFrame0 The position and orientation of the joint relative to actor0
\param[in] actor1 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localFrame1 The position and orientation of the joint relative to actor1
@see PxContactJoint
*/
PxContactJoint* PxContactJointCreate(PxPhysics& physics, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1);
/**
\brief a joint that maintains an upper or lower bound (or both) on the distance between two points on different objects
@see PxContactJointCreate PxJoint
*/
struct PxJacobianRow
{
PxVec3 linear0;
PxVec3 linear1;
PxVec3 angular0;
PxVec3 angular1;
PxJacobianRow(){}
PxJacobianRow(const PxVec3& lin0, const PxVec3& lin1, const PxVec3& ang0, const PxVec3& ang1) :
linear0(lin0), linear1(lin1), angular0(ang0), angular1(ang1)
{
}
void operator *= (const PxReal scale)
{
linear0 *= scale;
linear1 *= scale;
angular0 *= scale;
angular1 *= scale;
}
PxJacobianRow operator * (const PxReal scale) const
{
return PxJacobianRow(linear0*scale, linear1*scale, angular0*scale, angular1*scale);
}
};
/**
\brief a joint that maintains an upper or lower bound (or both) on the distance between two points on different objects
@see PxContactJointCreate PxJoint
*/
class PxContactJoint : public PxJoint
{
public:
/**
\brief Set the current contact of the joint
*/
virtual void setContact(const PxVec3& contact) = 0;
/**
\brief Set the current contact normal of the joint
*/
virtual void setContactNormal(const PxVec3& contactNormal) = 0;
/**
\brief Set the current penetration of the joint
*/
virtual void setPenetration(const PxReal penetration) = 0;
/**
\brief Return the current contact of the joint
*/
virtual PxVec3 getContact() const = 0;
/**
\brief Return the current contact normal of the joint
*/
virtual PxVec3 getContactNormal() const = 0;
/**
\brief Return the current penetration value of the joint
*/
virtual PxReal getPenetration() const = 0;
virtual PxReal getResititution() const = 0;
virtual void setResititution(const PxReal resititution) = 0;
virtual PxReal getBounceThreshold() const = 0;
virtual void setBounceThreshold(const PxReal bounceThreshold) = 0;
/**
\brief Returns string name of PxContactJoint, used for serialization
*/
virtual const char* getConcreteTypeName() const { return "PxContactJoint"; }
virtual void computeJacobians(PxJacobianRow* jacobian) const = 0;
virtual PxU32 getNbJacobianRows() const = 0;
protected:
//serialization
/**
\brief Constructor
*/
PX_INLINE PxContactJoint(PxType concreteType, PxBaseFlags baseFlags) : PxJoint(concreteType, baseFlags) {}
/**
\brief Deserialization constructor
*/
PX_INLINE PxContactJoint(PxBaseFlags baseFlags) : PxJoint(baseFlags) {}
/**
\brief Returns whether a given type name matches with the type of this instance
*/
virtual bool isKindOf(const char* name) const { return !::strcmp("PxContactJoint", name) || PxJoint::isKindOf(name); }
//~serialization
};
#if !PX_DOXYGEN
}
#endif
#endif

View File

@ -0,0 +1,73 @@
//
// 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-2018 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_EXTENSIONS_CONVEX_MESH_H
#define PX_PHYSICS_EXTENSIONS_CONVEX_MESH_H
/** \addtogroup extensions
@{
*/
#include "PxPhysXConfig.h"
#include "common/PxPhysXCommonConfig.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxConvexMeshGeometry;
/**
\brief Computes closest polygon of the convex hull geometry for a given impact point
and impact direction. When doing sweeps against a scene, one might want to delay
the rather expensive computation of the hit face index for convexes until it is clear
the information is really needed and then use this method to get the corresponding
face index.
\param[in] convexGeom The convex mesh geometry.
\param[in] geomPose Pose for the geometry object.
\param[in] impactPos Impact position.
\param[in] unitDir Normalized impact direction.
\return Closest face index of the convex geometry.
@see PxTransform PxConvexMeshGeometry
*/
PxU32 PxFindFaceIndex(const PxConvexMeshGeometry& convexGeom,
const PxTransform& geomPose,
const PxVec3& impactPos,
const PxVec3& unitDir);
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,561 @@
//
// 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-2018 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_D6JOINT_H
#define PX_D6JOINT_H
/** \addtogroup extensions
@{
*/
#include "extensions/PxJoint.h"
#include "extensions/PxJointLimit.h"
#include "foundation/PxFlags.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxD6Joint;
/**
\brief Create a D6 joint.
\param[in] physics The physics SDK
\param[in] actor0 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localFrame0 The position and orientation of the joint relative to actor0
\param[in] actor1 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localFrame1 The position and orientation of the joint relative to actor1
@see PxD6Joint
*/
PxD6Joint* PxD6JointCreate(PxPhysics& physics, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1);
/**
\brief Used to specify one of the degrees of freedom of a D6 joint.
@see PxD6Joint
*/
struct PxD6Axis
{
enum Enum
{
eX = 0, //!< motion along the X axis
eY = 1, //!< motion along the Y axis
eZ = 2, //!< motion along the Z axis
eTWIST = 3, //!< motion around the X axis
eSWING1 = 4, //!< motion around the Y axis
eSWING2 = 5, //!< motion around the Z axis
eCOUNT = 6
};
};
/**
\brief Used to specify the range of motions allowed for a degree of freedom in a D6 joint.
@see PxD6Joint
*/
struct PxD6Motion
{
enum Enum
{
eLOCKED, //!< The DOF is locked, it does not allow relative motion.
eLIMITED, //!< The DOF is limited, it only allows motion within a specific range.
eFREE //!< The DOF is free and has its full range of motion.
};
};
/**
\brief Used to specify which axes of a D6 joint are driven.
Each drive is an implicit force-limited damped spring:
force = spring * (target position - position) + damping * (targetVelocity - velocity)
Alternatively, the spring may be configured to generate a specified acceleration instead of a force.
A linear axis is affected by drive only if the corresponding drive flag is set. There are two possible models
for angular drive: swing/twist, which may be used to drive one or more angular degrees of freedom, or slerp,
which may only be used to drive all three angular degrees simultaneously.
@see PxD6Joint
*/
struct PxD6Drive
{
enum Enum
{
eX = 0, //!< drive along the X-axis
eY = 1, //!< drive along the Y-axis
eZ = 2, //!< drive along the Z-axis
eSWING = 3, //!< drive of displacement from the X-axis
eTWIST = 4, //!< drive of the displacement around the X-axis
eSLERP = 5, //!< drive of all three angular degrees along a SLERP-path
eCOUNT = 6
};
};
/**
\brief flags for configuring the drive model of a PxD6Joint
@see PxD6JointDrive PxD6Joint
*/
struct PxD6JointDriveFlag
{
enum Enum
{
eACCELERATION = 1 //!< drive spring is for the acceleration at the joint (rather than the force)
};
};
typedef PxFlags<PxD6JointDriveFlag::Enum, PxU32> PxD6JointDriveFlags;
PX_FLAGS_OPERATORS(PxD6JointDriveFlag::Enum, PxU32)
/**
\brief parameters for configuring the drive model of a PxD6Joint
@see PxD6Joint
*/
class PxD6JointDrive : public PxSpring
{
//= ATTENTION! =====================================================================================
// Changing the data layout of this class breaks the binary serialization format. See comments for
// PX_BINARY_SERIAL_VERSION. If a modification is required, please adjust the getBinaryMetaData
// function. If the modification is made on a custom branch, please change PX_BINARY_SERIAL_VERSION
// accordingly.
//==================================================================================================
public:
PxReal forceLimit; //!< the force limit of the drive - may be an impulse or a force depending on PxConstraintFlag::eDRIVE_LIMITS_ARE_FORCES
PxD6JointDriveFlags flags; //!< the joint drive flags
/**
\brief default constructor for PxD6JointDrive.
*/
PxD6JointDrive(): PxSpring(0,0), forceLimit(PX_MAX_F32), flags(0) {}
/**
\brief constructor a PxD6JointDrive.
\param[in] driveStiffness The stiffness of the drive spring.
\param[in] driveDamping The damping of the drive spring
\param[in] driveForceLimit The maximum impulse or force that can be exerted by the drive
\param[in] isAcceleration Whether the drive is an acceleration drive or a force drive
*/
PxD6JointDrive(PxReal driveStiffness, PxReal driveDamping, PxReal driveForceLimit, bool isAcceleration = false)
: PxSpring(driveStiffness, driveDamping)
, forceLimit(driveForceLimit)
, flags(isAcceleration?PxU32(PxD6JointDriveFlag::eACCELERATION) : 0)
{}
/**
\brief returns true if the drive is valid
*/
bool isValid() const
{
return PxIsFinite(stiffness) && stiffness>=0 &&
PxIsFinite(damping) && damping >=0 &&
PxIsFinite(forceLimit) && forceLimit >=0;
}
};
/**
\brief A D6 joint is a general constraint between two actors.
It allows the application to individually define the linear and rotational degrees of freedom,
and also to configure a variety of limits and driven degrees of freedom.
By default all degrees of freedom are locked. So to create a prismatic joint with free motion
along the x-axis:
\code
...
joint->setMotion(PxD6Axis::eX, PxD6JointMotion::eFREE);
...
\endcode
Or a Revolute joint with motion free allowed around the x-axis:
\code
...
joint->setMotion(PxD6Axis::eTWIST, PxD6JointMotion::eFREE);
...
\endcode
Degrees of freedom may also be set to limited instead of locked.
There are two different kinds of linear limits available. The first kind is a single limit value
for all linear degrees of freedom, which may act as a linear, circular, or spherical limit depending
on which degrees of freedom are limited. This is similar to a distance limit. Then, the second kind
supports a pair of limit values for each linear axis, which can be used to implement a traditional
prismatic joint for example.
If the twist degree of freedom is limited, is supports upper and lower limits. The two swing degrees
of freedom are limited with a cone limit.
@see PxD6JointCreate() PxJoint
*/
class PxD6Joint : public PxJoint
{
public:
/**
\brief Set the motion type around the specified axis.
Each axis may independently specify that the degree of freedom is locked (blocking relative movement
along or around this axis), limited by the corresponding limit, or free.
\param[in] axis the axis around which motion is specified
\param[in] type the motion type around the specified axis
<b>Default:</b> all degrees of freedom are locked
@see getMotion() PxD6Axis PxD6Motion
*/
virtual void setMotion(PxD6Axis::Enum axis, PxD6Motion::Enum type) = 0;
/**
\brief Get the motion type around the specified axis.
@see setMotion() PxD6Axis PxD6Motion
\param[in] axis the degree of freedom around which the motion type is specified
\return the motion type around the specified axis
*/
virtual PxD6Motion::Enum getMotion(PxD6Axis::Enum axis) const = 0;
/**
\brief get the twist angle of the joint, in the range (-2*Pi, 2*Pi]
*/
virtual PxReal getTwistAngle() const = 0;
/**
\brief get the twist angle of the joint
\deprecated Use getTwistAngle instead. Deprecated since PhysX version 4.0
*/
PX_DEPRECATED PX_FORCE_INLINE PxReal getTwist() const { return getTwistAngle(); }
/**
\brief get the swing angle of the joint from the Y axis
*/
virtual PxReal getSwingYAngle() const = 0;
/**
\brief get the swing angle of the joint from the Z axis
*/
virtual PxReal getSwingZAngle() const = 0;
/**
\brief Set the distance limit for the joint.
A single limit constraints all linear limited degrees of freedom, forming a linear, circular
or spherical constraint on motion depending on the number of limited degrees. This is similar
to a distance limit.
\param[in] limit the distance limit structure
@see getDistanceLimit() PxJointLinearLimit
*/
virtual void setDistanceLimit(const PxJointLinearLimit& limit) = 0;
/**
\brief Get the distance limit for the joint.
\return the distance limit structure
@see setDistanceLimit() PxJointLinearLimit
*/
virtual PxJointLinearLimit getDistanceLimit() const = 0;
/**
\deprecated Use setDistanceLimit instead. Deprecated since PhysX version 4.0
*/
PX_DEPRECATED PX_FORCE_INLINE void setLinearLimit(const PxJointLinearLimit& limit) { setDistanceLimit(limit); }
/**
\deprecated Use getDistanceLimit instead. Deprecated since PhysX version 4.0
*/
PX_DEPRECATED PX_FORCE_INLINE PxJointLinearLimit getLinearLimit() const { return getDistanceLimit(); }
/**
\brief Set the linear limit for a given linear axis.
This function extends the previous setDistanceLimit call with the following features:
- there can be a different limit for each linear axis
- each limit is defined by two values, i.e. it can now be asymmetric
This can be used to create prismatic joints similar to PxPrismaticJoint, or point-in-quad joints,
or point-in-box joints.
\param[in] axis The limited linear axis (must be PxD6Axis::eX, PxD6Axis::eY or PxD6Axis::eZ)
\param[in] limit The linear limit pair structure
@see getLinearLimit()
*/
virtual void setLinearLimit(PxD6Axis::Enum axis, const PxJointLinearLimitPair& limit) = 0;
/**
\brief Get the linear limit for a given linear axis.
\param[in] axis The limited linear axis (must be PxD6Axis::eX, PxD6Axis::eY or PxD6Axis::eZ)
\return the linear limit pair structure from desired axis
@see setLinearLimit() PxJointLinearLimit
*/
virtual PxJointLinearLimitPair getLinearLimit(PxD6Axis::Enum axis) const = 0;
/**
\brief Set the twist limit for the joint.
The twist limit controls the range of motion around the twist axis.
The limit angle range is (-2*Pi, 2*Pi).
\param[in] limit the twist limit structure
@see getTwistLimit() PxJointAngularLimitPair
*/
virtual void setTwistLimit(const PxJointAngularLimitPair& limit) = 0;
/**
\brief Get the twist limit for the joint.
\return the twist limit structure
@see setTwistLimit() PxJointAngularLimitPair
*/
virtual PxJointAngularLimitPair getTwistLimit() const = 0;
/**
\brief Set the swing cone limit for the joint.
The cone limit is used if either or both swing axes are limited. The extents are
symmetrical and measured in the frame of the parent. If only one swing degree of freedom
is limited, the corresponding value from the cone limit defines the limit range.
\param[in] limit the cone limit structure
@see getLimitCone() PxJointLimitCone
*/
virtual void setSwingLimit(const PxJointLimitCone& limit) = 0;
/**
\brief Get the cone limit for the joint.
\return the swing limit structure
@see setLimitCone() PxJointLimitCone
*/
virtual PxJointLimitCone getSwingLimit() const = 0;
/**
\brief Set a pyramidal swing limit for the joint.
The pyramid limits will only be used in the following cases:
- both swing Y and Z are limited. The limit shape is then a pyramid.
- Y is limited and Z is locked, or vice versa. The limit shape is an asymmetric angular section, similar to
what is supported for the twist axis.
The remaining cases (Y limited and Z is free, or vice versa) are not supported.
\param[in] limit the cone limit structure
@see getLimitCone() PxJointLimitPyramid
*/
virtual void setPyramidSwingLimit(const PxJointLimitPyramid& limit) = 0;
/**
\brief Get the pyramidal swing limit for the joint.
\return the swing limit structure
@see setLimitCone() PxJointLimitPyramid
*/
virtual PxJointLimitPyramid getPyramidSwingLimit() const = 0;
/**
\brief Set the drive parameters for the specified drive type.
\param[in] index the type of drive being specified
\param[in] drive the drive parameters
@see getDrive() PxD6JointDrive
<b>Default</b> The default drive spring and damping values are zero, the force limit is zero, and no flags are set.
*/
virtual void setDrive(PxD6Drive::Enum index, const PxD6JointDrive& drive) = 0;
/**
\brief Get the drive parameters for the specified drive type.
\param[in] index the specified drive type
@see setDrive() PxD6JointDrive
*/
virtual PxD6JointDrive getDrive(PxD6Drive::Enum index) const = 0;
/**
\brief Set the drive goal pose
The goal is relative to the constraint frame of actor[0]
<b>Default</b> the identity transform
\param[in] pose The goal drive pose if positional drive is in use.
\param[in] autowake Whether to wake the joint rigids up if it is asleep.
@see setDrivePosition()
*/
virtual void setDrivePosition(const PxTransform& pose, bool autowake = true) = 0;
/**
\brief Get the drive goal pose.
@see getDrivePosition()
*/
virtual PxTransform getDrivePosition() const = 0;
/**
\brief Set the target goal velocity for drive.
The velocity is measured in the constraint frame of actor[0]
\param[in] linear The goal velocity for linear drive
\param[in] angular The goal velocity for angular drive
\param[in] autowake Whether to wake the joint rigids up if it is asleep.
@see getDriveVelocity()
*/
virtual void setDriveVelocity(const PxVec3& linear, const PxVec3& angular, bool autowake = true) = 0;
/**
\brief Get the target goal velocity for joint drive.
\param[in] linear The goal velocity for linear drive
\param[in] angular The goal velocity for angular drive
@see setDriveVelocity()
*/
virtual void getDriveVelocity(PxVec3& linear, PxVec3& angular) const = 0;
/**
\brief Set the linear tolerance threshold for projection. Projection is enabled if PxConstraintFlag::ePROJECTION
is set for the joint.
If the joint separates by more than this distance along its locked degrees of freedom, the solver
will move the bodies to close the distance.
Setting a very small tolerance may result in simulation jitter or other artifacts.
Sometimes it is not possible to project (for example when the joints form a cycle).
<b>Range:</b> [0, PX_MAX_F32)<br>
<b>Default:</b> 1e10f
\param[in] tolerance the linear tolerance threshold
@see getProjectionLinearTolerance() PxJoint::setConstraintFlags() PxConstraintFlag::ePROJECTION
*/
virtual void setProjectionLinearTolerance(PxReal tolerance) = 0;
/**
\brief Get the linear tolerance threshold for projection.
\return the linear tolerance threshold
@see setProjectionLinearTolerance()
*/
virtual PxReal getProjectionLinearTolerance() const = 0;
/**
\brief Set the angular tolerance threshold for projection. Projection is enabled if
PxConstraintFlag::ePROJECTION is set for the joint.
If the joint deviates by more than this angle around its locked angular degrees of freedom,
the solver will move the bodies to close the angle.
Setting a very small tolerance may result in simulation jitter or other artifacts.
Sometimes it is not possible to project (for example when the joints form a cycle).
<b>Range:</b> [0,Pi] <br>
<b>Default:</b> Pi
\param[in] tolerance the angular tolerance threshold in radians
\note
Angular projection is implemented only for the case of two or three locked angular degrees of freedom.
@see getProjectionAngularTolerance() PxJoint::setConstraintFlag() PxConstraintFlag::ePROJECTION
*/
virtual void setProjectionAngularTolerance(PxReal tolerance) = 0;
/**
\brief Get the angular tolerance threshold for projection.
\return tolerance the angular tolerance threshold in radians
@see setProjectionAngularTolerance()
*/
virtual PxReal getProjectionAngularTolerance() const = 0;
/**
\brief Returns string name of PxD6Joint, used for serialization
*/
virtual const char* getConcreteTypeName() const { return "PxD6Joint"; }
protected:
//serialization
/**
\brief Constructor
*/
PX_INLINE PxD6Joint(PxType concreteType, PxBaseFlags baseFlags) : PxJoint(concreteType, baseFlags) {}
/**
\brief Deserialization constructor
*/
PX_INLINE PxD6Joint(PxBaseFlags baseFlags) : PxJoint(baseFlags) {}
/**
\brief Returns whether a given type name matches with the type of this instance
*/
virtual bool isKindOf(const char* name) const { return !::strcmp("PxD6Joint", name) || PxJoint::isKindOf(name); }
//~serialization
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,255 @@
//
// 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-2018 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_D6JOINT_CREATE_H
#define PX_D6JOINT_CREATE_H
#include "common/PxPhysXCommonConfig.h"
/** \addtogroup extensions
@{
*/
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxPhysics;
class PxRigidActor;
class PxJoint;
/**
\brief Helper function to create a fixed joint, using either a PxD6Joint or PxFixedJoint.
For fixed joints it is important that the joint frames have the same orientation. This helper function uses an identity rotation for both.
It is also important that the joint frames have an equivalent position in world space. The function does not check this, so it is up to users
to ensure that this is the case.
\param[in] physics The physics SDK
\param[in] actor0 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localPos0 The position of the joint relative to actor0
\param[in] actor1 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localPos1 The position of the joint relative to actor1
\param[in] useD6 True to use a PxD6Joint, false to use a PxFixedJoint;
\return The created joint.
@see PxD6Joint PxFixedJoint
*/
PxJoint* PxD6JointCreate_Fixed(PxPhysics& physics, PxRigidActor* actor0, const PxVec3& localPos0, PxRigidActor* actor1, const PxVec3& localPos1, bool useD6);
/**
\brief Helper function to create a distance joint, using either a PxD6Joint or PxDistanceJoint.
This helper function only supports a maximum distance constraint, because PxD6Joint does not support a minimum distance constraint (contrary
to PxDistanceJoint).
The distance is computed between the joint frames' world-space positions. The joint frames' orientations are irrelevant here so the function
sets them to identity.
\param[in] physics The physics SDK
\param[in] actor0 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localPos0 The position of the joint relative to actor0
\param[in] actor1 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localPos1 The position of the joint relative to actor1
\param[in] maxDist The maximum allowed distance
\param[in] useD6 True to use a PxD6Joint, false to use a PxDistanceJoint;
\return The created joint.
@see PxD6Joint PxDistanceJoint
*/
PxJoint* PxD6JointCreate_Distance(PxPhysics& physics, PxRigidActor* actor0, const PxVec3& localPos0, PxRigidActor* actor1, const PxVec3& localPos1, float maxDist, bool useD6);
/**
\brief Helper function to create a prismatic joint, using either a PxD6Joint or PxPrismaticJoint.
This function enforces that the joint frames have the same orientation, which is a local frame whose X is the desired translation axis.
This orientation is computed by the function, so users only have to define the desired translation axis (typically 1;0;0 or 0;1;0 or 0;0;1).
The translation can be limited. Limits are enforced if minLimit<maxLimit. If minLimit=maxLimit the axis is locked. If minLimit>maxLimit the
limits are not enforced and the axis is free. The limit values are computed relative to the position of actor0's joint frame.
The function creates hard limits, and uses PhysX's default contact distance parameter.
\param[in] physics The physics SDK
\param[in] actor0 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localPos0 The position of the joint relative to actor0
\param[in] actor1 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localPos1 The position of the joint relative to actor1
\param[in] axis The axis along which objects are allowed to move, expressed in the actors' local space
\param[in] minLimit The minimum allowed position along the axis
\param[in] maxLimit The maximum allowed position along the axis
\param[in] useD6 True to use a PxD6Joint, false to use a PxPrismaticJoint;
\return The created joint.
@see PxD6Joint PxPrismaticJoint
*/
PxJoint* PxD6JointCreate_Prismatic(PxPhysics& physics, PxRigidActor* actor0, const PxVec3& localPos0, PxRigidActor* actor1, const PxVec3& localPos1, const PxVec3& axis, float minLimit, float maxLimit, bool useD6);
/**
\brief Helper function to create a revolute joint, using either a PxD6Joint or PxRevoluteJoint.
This function enforces that the joint frames have the same orientation, which is a local frame whose X is the desired rotation axis.
This orientation is computed by the function, so users only have to define the desired rotation axis (typically 1;0;0 or 0;1;0 or 0;0;1).
The rotation can be limited. Limits are enforced if minLimit<maxLimit. If minLimit=maxLimit the axis is locked. If minLimit>maxLimit the
limits are not enforced and the axis is free. The limit values are computed relative to the rotation of actor0's joint frame.
The function creates hard limits, and uses PhysX's default contact distance parameter.
Limits are expressed in radians. Allowed range is ]-2*PI;+2*PI[
\param[in] physics The physics SDK
\param[in] actor0 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localPos0 The position of the joint relative to actor0
\param[in] actor1 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localPos1 The position of the joint relative to actor1
\param[in] axis The axis around which objects are allowed to move, expressed in the actors' local space
\param[in] minLimit The minimum allowed rotation along the axis
\param[in] maxLimit The maximum allowed rotation along the axis
\param[in] useD6 True to use a PxD6Joint, false to use a PxRevoluteJoint;
\return The created joint.
@see PxD6Joint PxRevoluteJoint
*/
PxJoint* PxD6JointCreate_Revolute(PxPhysics& physics, PxRigidActor* actor0, const PxVec3& localPos0, PxRigidActor* actor1, const PxVec3& localPos1, const PxVec3& axis, float minLimit, float maxLimit, bool useD6);
/**
\brief Helper function to create a spherical joint, using either a PxD6Joint or PxSphericalJoint.
This function supports a cone limit shape, defined by a cone axis and two angular limit values.
This function enforces that the joint frames have the same orientation, which is a local frame whose X is the desired cone axis.
This orientation is computed by the function, so users only have to define the desired cone axis (typically 1;0;0 or 0;1;0 or 0;0;1).
The rotations can be limited. Limits are enforced if limit1>0 and limit2>0. Otherwise the motion is free. The limit values define an ellipse,
which is the cross-section of the cone limit shape.
The function creates hard limits, and uses PhysX's default contact distance parameter.
Limits are expressed in radians. Allowed range is ]0;PI[. Limits are symmetric around the cone axis.
The cone axis is equivalent to the twist axis for the D6 joint. The twist motion is not limited.
\param[in] physics The physics SDK
\param[in] actor0 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localPos0 The position of the joint relative to actor0
\param[in] actor1 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localPos1 The position of the joint relative to actor1
\param[in] axis The cone axis, expressed in the actors' local space
\param[in] limit1 Max angular limit for the ellipse along the joint frame's second axis (first axis = cone axis)
\param[in] limit2 Max angular limit for the ellipse along the joint frame's third axis (first axis = cone axis)
\param[in] useD6 True to use a PxD6Joint, false to use a PxSphericalJoint;
\return The created joint.
@see PxD6Joint PxSphericalJoint
*/
PxJoint* PxD6JointCreate_Spherical(PxPhysics& physics, PxRigidActor* actor0, const PxVec3& localPos0, PxRigidActor* actor1, const PxVec3& localPos1, const PxVec3& axis, float limit1, float limit2, bool useD6);
/**
\brief Helper function to create a spherical joint, using either a PxD6Joint or PxSphericalJoint.
This function supports a cone limit shape, defined by two pairs of angular limit values. This can be used to create an asymmetric cone. If the
angular limit values are symmetric (i.e. minLimit1=-maxLimit1 and minLimit2=-maxLimit2) then the cone axis is the X axis in actor0's space.
If the limits are not symmetric, the function rotates the cone axis accordingly so that limits remain symmetric for PhysX. If this happens,
the initial joint frames will be different for both actors. By default minLimit1/maxLimit1 are limits around the joint's Y axis, and
minLimit2/maxLimit2 are limits around the joint's Z axis.
The function creates hard limits, and uses PhysX's default contact distance parameter.
Limits are expressed in radians. Allowed range is ]-PI;PI[.
The cone axis is equivalent to the twist axis for the D6 joint. The twist motion is not limited.
The returned apiroty and apirotz values can later be added to retrieved Y and Z swing angle values (from the joint), to remap
angle values to the given input range.
\param[out] apiroty Amount of rotation around Y used to setup actor0's joint frame
\param[out] apirotz Amount of rotation around Z used to setup actor0's joint frame
\param[in] physics The physics SDK
\param[in] actor0 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localPos0 The position of the joint relative to actor0
\param[in] actor1 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localPos1 The position of the joint relative to actor1
\param[in] minLimit1 Min angular limit along the joint frame's second axis (first axis = cone axis)
\param[in] maxLimit1 Max angular limit along the joint frame's second axis (first axis = cone axis)
\param[in] minLimit2 Min angular limit along the joint frame's third axis (first axis = cone axis)
\param[in] maxLimit2 Max angular limit along the joint frame's third axis (first axis = cone axis)
\param[in] useD6 True to use a PxD6Joint, false to use a PxSphericalJoint;
\return The created joint.
@see PxD6Joint PxSphericalJoint
*/
PxJoint* PxD6JointCreate_GenericCone(float& apiroty, float& apirotz, PxPhysics& physics, PxRigidActor* actor0, const PxVec3& localPos0, PxRigidActor* actor1, const PxVec3& localPos1, float minLimit1, float maxLimit1, float minLimit2, float maxLimit2, bool useD6);
/**
\brief Helper function to create a D6 joint with pyramidal swing limits.
This function supports a pyramid limit shape, defined by two pairs of angular limit values. This can be used to create an asymmetric pyramid. If the
angular limit values are symmetric (i.e. minLimit1=-maxLimit1 and minLimit2=-maxLimit2) then the pyramid axis is the X axis in actor0's space.
By default minLimit1/maxLimit1 are limits around the joint's Y axis, and minLimit2/maxLimit2 are limits around the joint's Z axis.
The function creates hard limits, and uses PhysX's default contact distance parameter.
Limits are expressed in radians. Allowed range is ]-PI;PI[.
The pyramid axis is equivalent to the twist axis for the D6 joint. The twist motion is not limited.
\param[in] physics The physics SDK
\param[in] actor0 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localPos0 The position of the joint relative to actor0
\param[in] actor1 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localPos1 The position of the joint relative to actor1
\param[in] axis The pyramid axis, expressed in the actors' local space
\param[in] minLimit1 Min angular limit along the joint frame's second axis (first axis = pyramid axis)
\param[in] maxLimit1 Max angular limit along the joint frame's second axis (first axis = pyramid axis)
\param[in] minLimit2 Min angular limit along the joint frame's third axis (first axis = pyramid axis)
\param[in] maxLimit2 Max angular limit along the joint frame's third axis (first axis = pyramid axis)
\return The created joint.
@see PxD6Joint
*/
PxJoint* PxD6JointCreate_Pyramid(PxPhysics& physics, PxRigidActor* actor0, const PxVec3& localPos0, PxRigidActor* actor1, const PxVec3& localPos1, const PxVec3& axis,
float minLimit1, float maxLimit1, float minLimit2, float maxLimit2);
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,110 @@
//
// 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-2018 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_DEFAULT_ALLOCATOR_H
#define PX_DEFAULT_ALLOCATOR_H
/** \addtogroup extensions
@{
*/
#include "foundation/PxAllocatorCallback.h"
#include "foundation/PxAssert.h"
#include "common/PxPhysXCommonConfig.h"
#include <stdlib.h>
#if PX_WINDOWS || PX_LINUX_FAMILY || PX_SWITCH
#include <malloc.h>
#endif
#if !PX_DOXYGEN
namespace physx
{
#endif
#if PX_WINDOWS
// on win32 we only have 8-byte alignment guaranteed, but the CRT provides special aligned allocation fns
PX_FORCE_INLINE void* platformAlignedAlloc(size_t size)
{
return _aligned_malloc(size, 16);
}
PX_FORCE_INLINE void platformAlignedFree(void* ptr)
{
_aligned_free(ptr);
}
#elif PX_LINUX_FAMILY || PX_SWITCH
PX_FORCE_INLINE void* platformAlignedAlloc(size_t size)
{
return ::memalign(16, size);
}
PX_FORCE_INLINE void platformAlignedFree(void* ptr)
{
::free(ptr);
}
#else
// on all other platforms we get 16-byte alignment by default
PX_FORCE_INLINE void* platformAlignedAlloc(size_t size)
{
return ::malloc(size);
}
PX_FORCE_INLINE void platformAlignedFree(void* ptr)
{
::free(ptr);
}
#endif
/**
\brief default implementation of the allocator interface required by the SDK
*/
class PxDefaultAllocator : public PxAllocatorCallback
{
public:
void* allocate(size_t size, const char*, const char*, int)
{
void* ptr = platformAlignedAlloc(size);
PX_ASSERT((reinterpret_cast<size_t>(ptr) & 15)==0);
return ptr;
}
void deallocate(void* ptr)
{
platformAlignedFree(ptr);
}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,98 @@
//
// 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-2018 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_EXTENSIONS_DEFAULT_CPU_DISPATCHER_H
#define PX_PHYSICS_EXTENSIONS_DEFAULT_CPU_DISPATCHER_H
/** \addtogroup extensions
@{
*/
#include "common/PxPhysXCommonConfig.h"
#include "task/PxCpuDispatcher.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief A default implementation for a CPU task dispatcher.
@see PxDefaultCpuDispatcherCreate() PxCpuDispatcher
*/
class PxDefaultCpuDispatcher: public PxCpuDispatcher
{
public:
/**
\brief Deletes the dispatcher.
Do not keep a reference to the deleted instance.
@see PxDefaultCpuDispatcherCreate()
*/
virtual void release() = 0;
/**
\brief Enables profiling at task level.
\note By default enabled only in profiling builds.
\param[in] runProfiled True if tasks should be profiled.
*/
virtual void setRunProfiled(bool runProfiled) = 0;
/**
\brief Checks if profiling is enabled at task level.
\return True if tasks should be profiled.
*/
virtual bool getRunProfiled() const = 0;
};
/**
\brief Create default dispatcher, extensions SDK needs to be initialized first.
\param[in] numThreads Number of worker threads the dispatcher should use.
\param[in] affinityMasks Array with affinity mask for each thread. If not defined, default masks will be used.
\note numThreads may be zero in which case no worker thread are initialized and
simulation tasks will be executed on the thread that calls PxScene::simulate()
@see PxDefaultCpuDispatcher
*/
PxDefaultCpuDispatcher* PxDefaultCpuDispatcherCreate(PxU32 numThreads, PxU32* affinityMasks = NULL);
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,62 @@
//
// 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-2018 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_EXTENSIONS_DEFAULT_ERROR_CALLBACK_H
#define PX_PHYSICS_EXTENSIONS_DEFAULT_ERROR_CALLBACK_H
#include "foundation/PxErrorCallback.h"
#include "PxPhysXConfig.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief default implementation of the error callback
This class is provided in order to enable the SDK to be started with the minimum of user code. Typically an application
will use its own error callback, and log the error to file or otherwise make it visible. Warnings and error messages from
the SDK are usually indicative that changes are required in order for PhysX to function correctly, and should not be ignored.
*/
class PxDefaultErrorCallback : public PxErrorCallback
{
public:
PxDefaultErrorCallback();
~PxDefaultErrorCallback();
virtual void reportError(PxErrorCode::Enum code, const char* message, const char* file, int line);
};
#if !PX_DOXYGEN
} // namespace physx
#endif
#endif

View File

@ -0,0 +1,263 @@
//
// 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-2018 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_EXTENSIONS_DEFAULTSIMULATIONFILTERSHADER_H
#define PX_PHYSICS_EXTENSIONS_DEFAULTSIMULATIONFILTERSHADER_H
/** \addtogroup extensions
@{
*/
#include "PxPhysXConfig.h"
#include "PxFiltering.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxActor;
/**
\brief 64-bit mask used for collision filtering.
The collision filtering equation for 2 objects o0 and o1 is:
<pre> (G0 op0 K0) op2 (G1 op1 K1) == b </pre>
with
<ul>
<li> G0 = PxGroupsMask for object o0. See PxSetGroupsMask </li>
<li> G1 = PxGroupsMask for object o1. See PxSetGroupsMask </li>
<li> K0 = filtering constant 0. See PxSetFilterConstants </li>
<li> K1 = filtering constant 1. See PxSetFilterConstants </li>
<li> b = filtering boolean. See PxSetFilterBool </li>
<li> op0, op1, op2 = filtering operations. See PxSetFilterOps </li>
</ul>
If the filtering equation is true, collision detection is enabled.
@see PxSetFilterOps()
*/
class PxGroupsMask
{
public:
PX_INLINE PxGroupsMask():bits0(0),bits1(0),bits2(0),bits3(0) {}
PX_INLINE ~PxGroupsMask() {}
PxU16 bits0, bits1, bits2, bits3;
};
/**
\brief Collision filtering operations.
@see PxGroupsMask
*/
struct PxFilterOp
{
enum Enum
{
PX_FILTEROP_AND,
PX_FILTEROP_OR,
PX_FILTEROP_XOR,
PX_FILTEROP_NAND,
PX_FILTEROP_NOR,
PX_FILTEROP_NXOR,
PX_FILTEROP_SWAP_AND
};
};
/**
\brief Implementation of a simple filter shader that emulates PhysX 2.8.x filtering
This shader provides the following logic:
\li If one of the two filter objects is a trigger, the pair is acccepted and #PxPairFlag::eTRIGGER_DEFAULT will be used for trigger reports
\li Else, if the filter mask logic (see further below) discards the pair it will be suppressed (#PxFilterFlag::eSUPPRESS)
\li Else, the pair gets accepted and collision response gets enabled (#PxPairFlag::eCONTACT_DEFAULT)
Filter mask logic:
Given the two #PxFilterData structures fd0 and fd1 of two collision objects, the pair passes the filter if the following
conditions are met:
1) Collision groups of the pair are enabled
2) Collision filtering equation is satisfied
@see PxSimulationFilterShader
*/
PxFilterFlags PxDefaultSimulationFilterShader(
PxFilterObjectAttributes attributes0,
PxFilterData filterData0,
PxFilterObjectAttributes attributes1,
PxFilterData filterData1,
PxPairFlags& pairFlags,
const void* constantBlock,
PxU32 constantBlockSize);
/**
\brief Determines if collision detection is performed between a pair of groups
\note Collision group is an integer between 0 and 31.
\param[in] group1 First Group
\param[in] group2 Second Group
\return True if the groups could collide
@see PxSetGroupCollisionFlag
*/
bool PxGetGroupCollisionFlag(const PxU16 group1, const PxU16 group2);
/**
\brief Specifies if collision should be performed by a pair of groups
\note Collision group is an integer between 0 and 31.
\param[in] group1 First Group
\param[in] group2 Second Group
\param[in] enable True to enable collision between the groups
@see PxGetGroupCollisionFlag
*/
void PxSetGroupCollisionFlag(const PxU16 group1, const PxU16 group2, const bool enable);
/**
\brief Retrieves the value set with PxSetGroup()
\note Collision group is an integer between 0 and 31.
\param[in] actor The actor
\return The collision group this actor belongs to
@see PxSetGroup
*/
PxU16 PxGetGroup(const PxActor& actor);
/**
\brief Sets which collision group this actor is part of
\note Collision group is an integer between 0 and 31.
\param[in] actor The actor
\param[in] collisionGroup Collision group this actor belongs to
@see PxGetGroup
*/
void PxSetGroup(PxActor& actor, const PxU16 collisionGroup);
/**
\brief Retrieves filtering operation. See comments for PxGroupsMask
\param[out] op0 First filter operator.
\param[out] op1 Second filter operator.
\param[out] op2 Third filter operator.
@see PxSetFilterOps PxSetFilterBool PxSetFilterConstants
*/
void PxGetFilterOps(PxFilterOp::Enum& op0, PxFilterOp::Enum& op1, PxFilterOp::Enum& op2);
/**
\brief Setups filtering operations. See comments for PxGroupsMask
\param[in] op0 Filter op 0.
\param[in] op1 Filter op 1.
\param[in] op2 Filter op 2.
@see PxSetFilterBool PxSetFilterConstants
*/
void PxSetFilterOps(const PxFilterOp::Enum& op0, const PxFilterOp::Enum& op1, const PxFilterOp::Enum& op2);
/**
\brief Retrieves filtering's boolean value. See comments for PxGroupsMask
\return flag Boolean value for filter.
@see PxSetFilterBool PxSetFilterConstants
*/
bool PxGetFilterBool();
/**
\brief Setups filtering's boolean value. See comments for PxGroupsMask
\param[in] enable Boolean value for filter.
@see PxSetFilterOps PxSsetFilterConstants
*/
void PxSetFilterBool(const bool enable);
/**
\brief Gets filtering constant K0 and K1. See comments for PxGroupsMask
\param[out] c0 the filtering constants, as a mask. See #PxGroupsMask.
\param[out] c1 the filtering constants, as a mask. See #PxGroupsMask.
@see PxSetFilterOps PxSetFilterBool PxSetFilterConstants
*/
void PxGetFilterConstants(PxGroupsMask& c0, PxGroupsMask& c1);
/**
\brief Setups filtering's K0 and K1 value. See comments for PxGroupsMask
\param[in] c0 The new group mask. See #PxGroupsMask.
\param[in] c1 The new group mask. See #PxGroupsMask.
@see PxSetFilterOps PxSetFilterBool PxGetFilterConstants
*/
void PxSetFilterConstants(const PxGroupsMask& c0, const PxGroupsMask& c1);
/**
\brief Gets 64-bit mask used for collision filtering. See comments for PxGroupsMask
\param[in] actor The actor
\return The group mask for the actor.
@see PxSetGroupsMask()
*/
PxGroupsMask PxGetGroupsMask(const PxActor& actor);
/**
\brief Sets 64-bit mask used for collision filtering. See comments for PxGroupsMask
\param[in] actor The actor
\param[in] mask The group mask to set for the actor.
@see PxGetGroupsMask()
*/
void PxSetGroupsMask(PxActor& actor, const PxGroupsMask& mask);
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,149 @@
//
// 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-2018 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_EXTENSIONS_DEFAULT_STREAMS_H
#define PX_PHYSICS_EXTENSIONS_DEFAULT_STREAMS_H
/** \addtogroup extensions
@{
*/
#include <stdio.h>
#include "common/PxPhysXCommonConfig.h"
#include "foundation/PxIO.h"
#include "PxFoundation.h"
typedef FILE* PxFileHandle;
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief default implementation of a memory write stream
@see PxOutputStream
*/
class PxDefaultMemoryOutputStream: public PxOutputStream
{
public:
PxDefaultMemoryOutputStream(PxAllocatorCallback &allocator = PxGetFoundation().getAllocatorCallback());
virtual ~PxDefaultMemoryOutputStream();
virtual PxU32 write(const void* src, PxU32 count);
virtual PxU32 getSize() const { return mSize; }
virtual PxU8* getData() const { return mData; }
private:
PxDefaultMemoryOutputStream(const PxDefaultMemoryOutputStream&);
PxDefaultMemoryOutputStream& operator=(const PxDefaultMemoryOutputStream&);
PxAllocatorCallback& mAllocator;
PxU8* mData;
PxU32 mSize;
PxU32 mCapacity;
};
/**
\brief default implementation of a memory read stream
@see PxInputData
*/
class PxDefaultMemoryInputData: public PxInputData
{
public:
PxDefaultMemoryInputData(PxU8* data, PxU32 length);
virtual PxU32 read(void* dest, PxU32 count);
virtual PxU32 getLength() const;
virtual void seek(PxU32 pos);
virtual PxU32 tell() const;
private:
PxU32 mSize;
const PxU8* mData;
PxU32 mPos;
};
/**
\brief default implementation of a file write stream
@see PxOutputStream
*/
class PxDefaultFileOutputStream: public PxOutputStream
{
public:
PxDefaultFileOutputStream(const char* name);
virtual ~PxDefaultFileOutputStream();
virtual PxU32 write(const void* src, PxU32 count);
virtual bool isValid();
private:
PxFileHandle mFile;
};
/**
\brief default implementation of a file read stream
@see PxInputData
*/
class PxDefaultFileInputData: public PxInputData
{
public:
PxDefaultFileInputData(const char* name);
virtual ~PxDefaultFileInputData();
virtual PxU32 read(void* dest, PxU32 count);
virtual void seek(PxU32 pos);
virtual PxU32 tell() const;
virtual PxU32 getLength() const;
bool isValid() const;
private:
PxFileHandle mFile;
PxU32 mLength;
};
#if !PX_DOXYGEN
}
#endif
/** @} */
#endif

View File

@ -0,0 +1,269 @@
//
// 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-2018 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_DISTANCEJOINT_H
#define PX_DISTANCEJOINT_H
/** \addtogroup extensions
@{
*/
#include "extensions/PxJoint.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxDistanceJoint;
/**
\brief Create a distance Joint.
\param[in] physics The physics SDK
\param[in] actor0 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localFrame0 The position and orientation of the joint relative to actor0
\param[in] actor1 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localFrame1 The position and orientation of the joint relative to actor1
@see PxDistanceJoint
*/
PxDistanceJoint* PxDistanceJointCreate(PxPhysics& physics, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1);
/**
\brief flags for configuring the drive of a PxDistanceJoint
@see PxDistanceJoint
*/
struct PxDistanceJointFlag
{
enum Enum
{
eMAX_DISTANCE_ENABLED = 1<<1,
eMIN_DISTANCE_ENABLED = 1<<2,
eSPRING_ENABLED = 1<<3
};
};
typedef PxFlags<PxDistanceJointFlag::Enum, PxU16> PxDistanceJointFlags;
PX_FLAGS_OPERATORS(PxDistanceJointFlag::Enum, PxU16)
/**
\brief a joint that maintains an upper or lower bound (or both) on the distance between two points on different objects
@see PxDistanceJointCreate PxJoint
*/
class PxDistanceJoint : public PxJoint
{
public:
/**
\brief Return the current distance of the joint
*/
virtual PxReal getDistance() const = 0;
/**
\brief Set the allowed minimum distance for the joint.
The minimum distance must be no more than the maximum distance
<b>Default</b> 0.0f
<b>Range</b> [0, PX_MAX_F32)
\param[in] distance the minimum distance
@see PxDistanceJoint::minDistance, PxDistanceJointFlag::eMIN_DISTANCE_ENABLED getMinDistance()
*/
virtual void setMinDistance(PxReal distance) = 0;
/**
\brief Get the allowed minimum distance for the joint.
\return the allowed minimum distance
@see PxDistanceJoint::minDistance, PxDistanceJointFlag::eMIN_DISTANCE_ENABLED setMinDistance()
*/
virtual PxReal getMinDistance() const = 0;
/**
\brief Set the allowed maximum distance for the joint.
The maximum distance must be no less than the minimum distance.
<b>Default</b> 0.0f
<b>Range</b> [0, PX_MAX_F32)
\param[in] distance the maximum distance
@see PxDistanceJoint::maxDistance, PxDistanceJointFlag::eMAX_DISTANCE_ENABLED getMinDistance()
*/
virtual void setMaxDistance(PxReal distance) = 0;
/**
\brief Get the allowed maximum distance for the joint.
\return the allowed maximum distance
@see PxDistanceJoint::maxDistance, PxDistanceJointFlag::eMAX_DISTANCE_ENABLED setMaxDistance()
*/
virtual PxReal getMaxDistance() const = 0;
/**
\brief Set the error tolerance of the joint.
\param[in] tolerance the distance beyond the allowed range at which the joint becomes active
@see PxDistanceJoint::tolerance, getTolerance()
*/
virtual void setTolerance(PxReal tolerance) = 0;
/**
\brief Get the error tolerance of the joint.
the distance beyond the joint's [min, max] range before the joint becomes active.
<b>Default</b> 0.25f * PxTolerancesScale::length
<b>Range</b> (0, PX_MAX_F32)
This value should be used to ensure that if the minimum distance is zero and the
spring function is in use, the rest length of the spring is non-zero.
@see PxDistanceJoint::tolerance, setTolerance()
*/
virtual PxReal getTolerance() const = 0;
/**
\brief Set the strength of the joint spring.
The spring is used if enabled, and the distance exceeds the range [min-error, max+error].
<b>Default</b> 0.0f
<b>Range</b> [0, PX_MAX_F32)
\param[in] stiffness the spring strength of the joint
@see PxDistanceJointFlag::eSPRING_ENABLED getStiffness()
*/
virtual void setStiffness(PxReal stiffness) = 0;
/**
\brief Get the strength of the joint spring.
\return stiffness the spring strength of the joint
@see PxDistanceJointFlag::eSPRING_ENABLED setStiffness()
*/
virtual PxReal getStiffness() const = 0;
/**
\brief Set the damping of the joint spring.
The spring is used if enabled, and the distance exceeds the range [min-error, max+error].
<b>Default</b> 0.0f
<b>Range</b> [0, PX_MAX_F32)
\param[in] damping the degree of damping of the joint spring of the joint
@see PxDistanceJointFlag::eSPRING_ENABLED setDamping()
*/
virtual void setDamping(PxReal damping) = 0;
/**
\brief Get the damping of the joint spring.
\return the degree of damping of the joint spring of the joint
@see PxDistanceJointFlag::eSPRING_ENABLED setDamping()
*/
virtual PxReal getDamping() const = 0;
/**
\brief Set the flags specific to the Distance Joint.
<b>Default</b> PxDistanceJointFlag::eMAX_DISTANCE_ENABLED
\param[in] flags The joint flags.
@see PxDistanceJointFlag setFlag() getFlags()
*/
virtual void setDistanceJointFlags(PxDistanceJointFlags flags) = 0;
/**
\brief Set a single flag specific to a Distance Joint to true or false.
\param[in] flag The flag to set or clear.
\param[in] value the value to which to set the flag
@see PxDistanceJointFlag, getFlags() setFlags()
*/
virtual void setDistanceJointFlag(PxDistanceJointFlag::Enum flag, bool value) = 0;
/**
\brief Get the flags specific to the Distance Joint.
\return the joint flags
@see PxDistanceJoint::flags, PxDistanceJointFlag setFlag() setFlags()
*/
virtual PxDistanceJointFlags getDistanceJointFlags() const = 0;
/**
\brief Returns string name of PxDistanceJoint, used for serialization
*/
virtual const char* getConcreteTypeName() const { return "PxDistanceJoint"; }
protected:
//serialization
/**
\brief Constructor
*/
PX_INLINE PxDistanceJoint(PxType concreteType, PxBaseFlags baseFlags) : PxJoint(concreteType, baseFlags) {}
/**
\brief Deserialization constructor
*/
PX_INLINE PxDistanceJoint(PxBaseFlags baseFlags) : PxJoint(baseFlags) {}
/**
\brief Returns whether a given type name matches with the type of this instance
*/
virtual bool isKindOf(const char* name) const { return !::strcmp("PxDistanceJoint", name) || PxJoint::isKindOf(name); }
//~serialization
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,88 @@
//
// 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-2018 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_EXTENSIONS_API_H
#define PX_EXTENSIONS_API_H
/** \addtogroup extensions
@{
*/
#include "foundation/PxErrorCallback.h"
#include "extensions/PxDefaultAllocator.h"
#include "extensions/PxConstraintExt.h"
#include "extensions/PxDistanceJoint.h"
#include "extensions/PxContactJoint.h"
#include "extensions/PxFixedJoint.h"
#include "extensions/PxPrismaticJoint.h"
#include "extensions/PxRevoluteJoint.h"
#include "extensions/PxSphericalJoint.h"
#include "extensions/PxD6Joint.h"
#include "extensions/PxDefaultSimulationFilterShader.h"
#include "extensions/PxDefaultErrorCallback.h"
#include "extensions/PxDefaultStreams.h"
#include "extensions/PxRigidActorExt.h"
#include "extensions/PxRigidBodyExt.h"
#include "extensions/PxShapeExt.h"
#include "extensions/PxTriangleMeshExt.h"
#include "extensions/PxSerialization.h"
#include "extensions/PxDefaultCpuDispatcher.h"
#include "extensions/PxSmoothNormals.h"
#include "extensions/PxSimpleFactory.h"
#include "extensions/PxStringTableExt.h"
#include "extensions/PxBroadPhaseExt.h"
#include "extensions/PxMassProperties.h"
#include "extensions/PxSceneQueryExt.h"
/** \brief Initialize the PhysXExtensions library.
This should be called before calling any functions or methods in extensions which may require allocation.
\note This function does not need to be called before creating a PxDefaultAllocator object.
\param physics a PxPhysics object
\param pvd an PxPvd (PhysX Visual Debugger) object
@see PxCloseExtensions PxFoundation PxPhysics
*/
PX_C_EXPORT bool PX_CALL_CONV PxInitExtensions(physx::PxPhysics& physics, physx::PxPvd* pvd);
/** \brief Shut down the PhysXExtensions library.
This function should be called to cleanly shut down the PhysXExtensions library before application exit.
\note This function is required to be called to release foundation usage.
@see PxInitExtensions
*/
PX_C_EXPORT void PX_CALL_CONV PxCloseExtensions();
/** @} */
#endif // PX_EXTENSIONS_API_H

View File

@ -0,0 +1,159 @@
//
// 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-2018 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_FIXEDJOINT_H
#define PX_FIXEDJOINT_H
/** \addtogroup extensions
@{
*/
#include "extensions/PxJoint.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxFixedJoint;
/**
\brief Create a fixed joint.
\param[in] physics The physics SDK
\param[in] actor0 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localFrame0 The position and orientation of the joint relative to actor0
\param[in] actor1 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localFrame1 The position and orientation of the joint relative to actor1
@see PxFixedJoint
*/
PxFixedJoint* PxFixedJointCreate(PxPhysics& physics, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1);
/**
\brief A fixed joint permits no relative movement between two bodies. ie the bodies are glued together.
\image html fixedJoint.png
@see PxFixedJointCreate() PxJoint
*/
class PxFixedJoint : public PxJoint
{
public:
/**
\brief Set the linear tolerance threshold for projection. Projection is enabled if PxConstraintFlag::ePROJECTION
is set for the joint.
If the joint separates by more than this distance along its locked degrees of freedom, the solver
will move the bodies to close the distance.
Setting a very small tolerance may result in simulation jitter or other artifacts.
Sometimes it is not possible to project (for example when the joints form a cycle).
<b>Range:</b> [0, PX_MAX_F32)<br>
<b>Default:</b> 1e10f
\param[in] tolerance the linear tolerance threshold
@see getProjectionLinearTolerance() PxJoint::setConstraintFlags() PxConstraintFlag::ePROJECTION
*/
virtual void setProjectionLinearTolerance(PxReal tolerance) = 0;
/**
\brief Get the linear tolerance threshold for projection.
\return the linear tolerance threshold
@see setProjectionLinearTolerance() PxJoint::setConstraintFlag()
*/
virtual PxReal getProjectionLinearTolerance() const = 0;
/**
\brief Set the angular tolerance threshold for projection. Projection is enabled if
PxConstraintFlag::ePROJECTION is set for the joint.
If the joint deviates by more than this angle around its locked angular degrees of freedom,
the solver will move the bodies to close the angle.
Setting a very small tolerance may result in simulation jitter or other artifacts.
Sometimes it is not possible to project (for example when the joints form a cycle).
<b>Range:</b> [0,Pi] <br>
<b>Default:</b> Pi
\param[in] tolerance the angular tolerance threshold in radians
@see getProjectionAngularTolerance() PxJoint::setConstraintFlag() PxConstraintFlag::ePROJECTION
*/
virtual void setProjectionAngularTolerance(PxReal tolerance) = 0;
/**
\brief Get the angular tolerance threshold for projection.
\return the angular tolerance threshold in radians
@see setProjectionAngularTolerance()
*/
virtual PxReal getProjectionAngularTolerance() const = 0;
/**
\brief Returns string name of PxFixedJoint, used for serialization
*/
virtual const char* getConcreteTypeName() const { return "PxFixedJoint"; }
protected:
//serialization
/**
\brief Constructor
*/
PX_INLINE PxFixedJoint(PxType concreteType, PxBaseFlags baseFlags) : PxJoint(concreteType, baseFlags) {}
/**
\brief Deserialization constructor
*/
PX_INLINE PxFixedJoint(PxBaseFlags baseFlags) : PxJoint(baseFlags) {}
/**
\brief Returns whether a given type name matches with the type of this instance
*/
virtual bool isKindOf(const char* name) const { return !::strcmp("PxFixedJoint", name) || PxJoint::isKindOf(name); }
//~serialization
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,419 @@
//
// 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-2018 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_JOINTCONSTRAINT_H
#define PX_JOINTCONSTRAINT_H
/** \addtogroup extensions
@{
*/
#include "foundation/PxTransform.h"
#include "PxRigidActor.h"
#include "PxConstraint.h"
#include "common/PxBase.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxRigidActor;
class PxScene;
class PxPhysics;
class PxConstraint;
/**
\brief an enumeration of PhysX' built-in joint types
@see PxJoint
*/
struct PxJointConcreteType
{
enum Enum
{
eSPHERICAL = PxConcreteType::eFIRST_PHYSX_EXTENSION,
eREVOLUTE,
ePRISMATIC,
eFIXED,
eDISTANCE,
eD6,
eCONTACT,
eLast
};
};
PX_DEFINE_TYPEINFO(PxJoint, PxConcreteType::eUNDEFINED)
PX_DEFINE_TYPEINFO(PxD6Joint, PxJointConcreteType::eD6)
PX_DEFINE_TYPEINFO(PxDistanceJoint, PxJointConcreteType::eDISTANCE)
PX_DEFINE_TYPEINFO(PxContactJoint, PxJointConcreteType::eCONTACT)
PX_DEFINE_TYPEINFO(PxFixedJoint, PxJointConcreteType::eFIXED)
PX_DEFINE_TYPEINFO(PxPrismaticJoint, PxJointConcreteType::ePRISMATIC)
PX_DEFINE_TYPEINFO(PxRevoluteJoint, PxJointConcreteType::eREVOLUTE)
PX_DEFINE_TYPEINFO(PxSphericalJoint, PxJointConcreteType::eSPHERICAL)
/**
\brief an enumeration for specifying one or other of the actors referenced by a joint
@see PxJoint
*/
struct PxJointActorIndex
{
enum Enum
{
eACTOR0,
eACTOR1,
COUNT
};
};
/**
\brief a base interface providing common functionality for PhysX joints
*/
class PxJoint : public PxBase
{
//= ATTENTION! =====================================================================================
// Changing the data layout of this class breaks the binary serialization format. See comments for
// PX_BINARY_SERIAL_VERSION. If a modification is required, please adjust the getBinaryMetaData
// function. If the modification is made on a custom branch, please change PX_BINARY_SERIAL_VERSION
// accordingly.
//==================================================================================================
public:
/**
\brief Set the actors for this joint.
An actor may be NULL to indicate the world frame. At most one of the actors may be NULL.
\param[in] actor0 the first actor.
\param[in] actor1 the second actor
@see getActors()
*/
virtual void setActors(PxRigidActor* actor0, PxRigidActor* actor1) = 0;
/**
\brief Get the actors for this joint.
\param[out] actor0 the first actor.
\param[out] actor1 the second actor
@see setActors()
*/
virtual void getActors(PxRigidActor*& actor0, PxRigidActor*& actor1) const = 0;
/**
\brief Set the joint local pose for an actor.
This is the relative pose which locates the joint frame relative to the actor.
\param[in] actor 0 for the first actor, 1 for the second actor.
\param[in] localPose the local pose for the actor this joint
@see getLocalPose()
*/
virtual void setLocalPose(PxJointActorIndex::Enum actor, const PxTransform& localPose) = 0;
/**
\brief get the joint local pose for an actor.
\param[in] actor 0 for the first actor, 1 for the second actor.
return the local pose for this joint
@see setLocalPose()
*/
virtual PxTransform getLocalPose(PxJointActorIndex::Enum actor) const = 0;
/**
\brief get the relative pose for this joint
This function returns the pose of the joint frame of actor1 relative to actor0
*/
virtual PxTransform getRelativeTransform() const = 0;
/**
\brief get the relative linear velocity of the joint
This function returns the linear velocity of the origin of the constraint frame of actor1, relative to the origin of the constraint
frame of actor0. The value is returned in the constraint frame of actor0
*/
virtual PxVec3 getRelativeLinearVelocity() const = 0;
/**
\brief get the relative angular velocity of the joint
This function returns the angular velocity of actor1 relative to actor0. The value is returned in the constraint frame of actor0
*/
virtual PxVec3 getRelativeAngularVelocity() const = 0;
/**
\brief set the break force for this joint.
if the constraint force or torque on the joint exceeds the specified values, the joint will break,
at which point it will not constrain the two actors and the flag PxConstraintFlag::eBROKEN will be set. The
force and torque are measured in the joint frame of the first actor
\param[in] force the maximum force the joint can apply before breaking
\param[in] torque the maximum torque the joint can apply before breaking
*/
virtual void setBreakForce(PxReal force, PxReal torque) = 0;
/**
\brief get the break force for this joint.
\param[out] force the maximum force the joint can apply before breaking
\param[out] torque the maximum torque the joint can apply before breaking
@see setBreakForce()
*/
virtual void getBreakForce(PxReal& force, PxReal& torque) const = 0;
/**
\brief set the constraint flags for this joint.
\param[in] flags the constraint flags
@see PxConstraintFlag
*/
virtual void setConstraintFlags(PxConstraintFlags flags) = 0;
/**
\brief set a constraint flags for this joint to a specified value.
\param[in] flag the constraint flag
\param[in] value the value to which to set the flag
@see PxConstraintFlag
*/
virtual void setConstraintFlag(PxConstraintFlag::Enum flag, bool value) = 0;
/**
\brief get the constraint flags for this joint.
\return the constraint flags
@see PxConstraintFlag
*/
virtual PxConstraintFlags getConstraintFlags() const = 0;
/**
\brief set the inverse mass scale for actor0.
\param[in] invMassScale the scale to apply to the inverse mass of actor 0 for resolving this constraint
@see getInvMassScale0
*/
virtual void setInvMassScale0(PxReal invMassScale) = 0;
/**
\brief get the inverse mass scale for actor0.
\return inverse mass scale for actor0
@see setInvMassScale0
*/
virtual PxReal getInvMassScale0() const = 0;
/**
\brief set the inverse inertia scale for actor0.
\param[in] invInertiaScale the scale to apply to the inverse inertia of actor0 for resolving this constraint
@see getInvMassScale0
*/
virtual void setInvInertiaScale0(PxReal invInertiaScale) = 0;
/**
\brief get the inverse inertia scale for actor0.
\return inverse inertia scale for actor0
@see setInvInertiaScale0
*/
virtual PxReal getInvInertiaScale0() const = 0;
/**
\brief set the inverse mass scale for actor1.
\param[in] invMassScale the scale to apply to the inverse mass of actor 1 for resolving this constraint
@see getInvMassScale1
*/
virtual void setInvMassScale1(PxReal invMassScale) = 0;
/**
\brief get the inverse mass scale for actor1.
\return inverse mass scale for actor1
@see setInvMassScale1
*/
virtual PxReal getInvMassScale1() const = 0;
/**
\brief set the inverse inertia scale for actor1.
\param[in] invInertiaScale the scale to apply to the inverse inertia of actor1 for resolving this constraint
@see getInvInertiaScale1
*/
virtual void setInvInertiaScale1(PxReal invInertiaScale) = 0;
/**
\brief get the inverse inertia scale for actor1.
\return inverse inertia scale for actor1
@see setInvInertiaScale1
*/
virtual PxReal getInvInertiaScale1() const = 0;
/**
\brief Retrieves the PxConstraint corresponding to this joint.
This can be used to determine, among other things, the force applied at the joint.
\return the constraint
*/
virtual PxConstraint* getConstraint() 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 Deletes the joint.
\note This call does not wake up the connected rigid bodies.
*/
virtual void release() = 0;
/**
\brief Retrieves the scene which this joint belongs to.
\return Owner Scene. NULL if not part of a scene.
@see PxScene
*/
virtual PxScene* getScene() const = 0;
void* userData; //!< user can assign this to whatever, usually to create a 1:1 relationship with a user object.
//serialization
/**
\brief Put class meta data in stream, used for serialization
*/
static void getBinaryMetaData(PxOutputStream& stream);
//~serialization
protected:
virtual ~PxJoint() {}
//serialization
/**
\brief Constructor
*/
PX_INLINE PxJoint(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags), userData(NULL) {}
/**
\brief Deserialization constructor
*/
PX_INLINE PxJoint(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
/**
\brief Returns whether a given type name matches with the type of this instance
*/
virtual bool isKindOf(const char* name) const { return !::strcmp("PxJoint", name) || PxBase::isKindOf(name); }
//~serialization
};
class PxSpring
{
//= ATTENTION! =====================================================================================
// Changing the data layout of this class breaks the binary serialization format. See comments for
// PX_BINARY_SERIAL_VERSION. If a modification is required, please adjust the getBinaryMetaData
// function. If the modification is made on a custom branch, please change PX_BINARY_SERIAL_VERSION
// accordingly.
//==================================================================================================
public:
PxReal stiffness; //!< the spring strength of the drive: that is, the force proportional to the position error
PxReal damping; //!< the damping strength of the drive: that is, the force proportional to the velocity error
PxSpring(PxReal stiffness_, PxReal damping_): stiffness(stiffness_), damping(damping_) {}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** \brief Helper function to setup a joint's global frame
This replaces the following functions from previous SDK versions:
void NxJointDesc::setGlobalAnchor(const NxVec3& wsAnchor);
void NxJointDesc::setGlobalAxis(const NxVec3& wsAxis);
The function sets the joint's localPose using world-space input parameters.
\param[in] wsAnchor Global frame anchor point. <b>Range:</b> position vector
\param[in] wsAxis Global frame axis. <b>Range:</b> direction vector
\param[in,out] joint Joint having its global frame set.
*/
PX_C_EXPORT void PX_CALL_CONV PxSetJointGlobalFrame(physx::PxJoint& joint, const physx::PxVec3* wsAnchor, const physx::PxVec3* wsAxis);
/** @} */
#endif

View File

@ -0,0 +1,566 @@
//
// 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-2018 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_EXTENSIONS_JOINT_LIMIT
#define PX_EXTENSIONS_JOINT_LIMIT
/** \addtogroup extensions
@{
*/
#include "foundation/PxMath.h"
#include "PxPhysXConfig.h"
#include "common/PxTolerancesScale.h"
#include "PxJoint.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Describes the parameters for a joint limit.
Limits are enabled or disabled by setting flags or other configuration parameters joints, see the
documentation for specific joint types for details.
*/
class PxJointLimitParameters
{
//= ATTENTION! =====================================================================================
// Changing the data layout of this class breaks the binary serialization format. See comments for
// PX_BINARY_SERIAL_VERSION. If a modification is required, please adjust the getBinaryMetaData
// function. If the modification is made on a custom branch, please change PX_BINARY_SERIAL_VERSION
// accordingly.
//==================================================================================================
public:
/**
\brief Controls the amount of bounce when the joint hits a limit.
A restitution value of 1.0 causes the joint to bounce back with the velocity which it hit the limit.
A value of zero causes the joint to stop dead.
In situations where the joint has many locked DOFs (e.g. 5) the restitution may not be applied
correctly. This is due to a limitation in the solver which causes the restitution velocity to become zero
as the solver enforces constraints on the other DOFs.
This limitation applies to both angular and linear limits, however it is generally most apparent with limited
angular DOFs. Disabling joint projection and increasing the solver iteration count may improve this behavior
to some extent.
Also, combining soft joint limits with joint drives driving against those limits may affect stability.
<b>Range:</b> [0,1]<br>
<b>Default:</b> 0.0
*/
PxReal restitution;
/**
determines the minimum impact velocity which will cause the joint to bounce
*/
PxReal bounceThreshold;
/**
\brief if greater than zero, the limit is soft, i.e. a spring pulls the joint back to the limit
<b>Range:</b> [0, PX_MAX_F32)<br>
<b>Default:</b> 0.0
*/
PxReal stiffness;
/**
\brief if spring is greater than zero, this is the damping of the limit spring
<b>Range:</b> [0, PX_MAX_F32)<br>
<b>Default:</b> 0.0
*/
PxReal damping;
/**
\brief the distance inside the limit value at which the limit will be considered to be active by the
solver. As this value is made larger, the limit becomes active more quickly. It thus becomes less
likely to violate the extents of the limit, but more expensive.
The contact distance should be less than the limit angle or distance, and in the case of a pair limit,
less than half the distance between the upper and lower bounds. Exceeding this value will result in
the limit being active all the time.
Making this value too small can result in jitter around the limit.
<b>Default:</b> depends on the joint
@see PxPhysics::getTolerancesScale()
*/
PxReal contactDistance;
PxJointLimitParameters() :
restitution (0.0f),
bounceThreshold (0.0f),
stiffness (0.0f),
damping (0.0f),
contactDistance (0.0f)
{
}
PxJointLimitParameters(const PxJointLimitParameters& p) :
restitution (p.restitution),
bounceThreshold (p.bounceThreshold),
stiffness (p.stiffness),
damping (p.damping),
contactDistance (p.contactDistance)
{
}
/**
\brief Returns true if the current settings are valid.
\return true if the current settings are valid
*/
PX_INLINE bool isValid() const
{
return PxIsFinite(restitution) && restitution >= 0 && restitution <= 1 &&
PxIsFinite(stiffness) && stiffness >= 0 &&
PxIsFinite(damping) && damping >= 0 &&
PxIsFinite(bounceThreshold) && bounceThreshold >= 0 &&
PxIsFinite(contactDistance) && contactDistance >= 0;
}
PX_INLINE bool isSoft() const
{
return damping>0 || stiffness>0;
}
protected:
~PxJointLimitParameters() {}
};
/**
\brief Describes a one-sided linear limit.
*/
class PxJointLinearLimit : public PxJointLimitParameters
{
//= ATTENTION! =====================================================================================
// Changing the data layout of this class breaks the binary serialization format. See comments for
// PX_BINARY_SERIAL_VERSION. If a modification is required, please adjust the getBinaryMetaData
// function. If the modification is made on a custom branch, please change PX_BINARY_SERIAL_VERSION
// accordingly.
//==================================================================================================
public:
/**
\brief the extent of the limit.
<b>Range:</b> (0, PX_MAX_F32) <br>
<b>Default:</b> PX_MAX_F32
*/
PxReal value;
/**
\brief construct a linear hard limit
\param[in] scale A PxTolerancesScale struct. Should be the same as used when creating the PxPhysics object.
\param[in] extent The extent of the limit
\param[in] contactDist The distance from the limit at which it becomes active. Default is 0.01f scaled by the tolerance length scale
@see PxJointLimitParameters PxTolerancesScale
*/
PxJointLinearLimit(const PxTolerancesScale& scale, PxReal extent, PxReal contactDist = -1.0f)
: value(extent)
{
PxJointLimitParameters::contactDistance = contactDist == -1.0f ? 0.01f*scale.length : contactDist;
}
/**
\brief construct a linear soft limit
\param[in] extent the extent of the limit
\param[in] spring the stiffness and damping parameters for the limit spring
@see PxJointLimitParameters PxTolerancesScale
*/
PxJointLinearLimit(PxReal extent, const PxSpring& spring) : value(extent)
{
stiffness = spring.stiffness;
damping = spring.damping;
}
/**
\brief Returns true if the limit is valid
\return true if the current settings are valid
*/
PX_INLINE bool isValid() const
{
return PxJointLimitParameters::isValid() &&
PxIsFinite(value) &&
value > 0.0f;
}
};
/**
\brief Describes a two-sided limit.
*/
class PxJointLinearLimitPair : public PxJointLimitParameters
{
//= ATTENTION! =====================================================================================
// Changing the data layout of this class breaks the binary serialization format. See comments for
// PX_BINARY_SERIAL_VERSION. If a modification is required, please adjust the getBinaryMetaData
// function. If the modification is made on a custom branch, please change PX_BINARY_SERIAL_VERSION
// accordingly.
//==================================================================================================
public:
/**
\brief the range of the limit. The upper limit must be no lower than the
lower limit, and if they are equal the limited degree of freedom will be treated as locked.
<b>Range:</b> See the joint on which the limit is used for details<br>
<b>Default:</b> lower = -PX_MAX_F32/3, upper = PX_MAX_F32/3
*/
PxReal upper, lower;
/**
\brief Construct a linear hard limit pair. The lower distance value must be less than the upper distance value.
\param[in] scale A PxTolerancesScale struct. Should be the same as used when creating the PxPhysics object.
\param[in] lowerLimit The lower distance of the limit
\param[in] upperLimit The upper distance of the limit
\param[in] contactDist The distance from the limit at which it becomes active. Default is the lesser of 0.01f scaled by the tolerance length scale, and 0.49 * (upperLimit - lowerLimit)
@see PxJointLimitParameters PxTolerancesScale
*/
PxJointLinearLimitPair(const PxTolerancesScale& scale, PxReal lowerLimit = -PX_MAX_F32/3.0f, PxReal upperLimit = PX_MAX_F32/3.0f, PxReal contactDist = -1.0f) :
upper(upperLimit),
lower(lowerLimit)
{
PxJointLimitParameters::contactDistance = contactDist == -1.0f ? PxMin(scale.length * 0.01f, (upperLimit*0.49f-lowerLimit*0.49f)) : contactDist;
bounceThreshold = 2.0f*scale.length;
}
/**
\brief construct a linear soft limit pair
\param[in] lowerLimit The lower distance of the limit
\param[in] upperLimit The upper distance of the limit
\param[in] spring The stiffness and damping parameters of the limit spring
@see PxJointLimitParameters PxTolerancesScale
*/
PxJointLinearLimitPair(PxReal lowerLimit, PxReal upperLimit, const PxSpring& spring) :
upper(upperLimit),
lower(lowerLimit)
{
stiffness = spring.stiffness;
damping = spring.damping;
}
/**
\brief Returns true if the limit is valid.
\return true if the current settings are valid
*/
PX_INLINE bool isValid() const
{
return PxJointLimitParameters::isValid() &&
PxIsFinite(upper) && PxIsFinite(lower) && upper >= lower &&
PxIsFinite(upper - lower);
}
};
class PxJointAngularLimitPair : public PxJointLimitParameters
{
//= ATTENTION! =====================================================================================
// Changing the data layout of this class breaks the binary serialization format. See comments for
// PX_BINARY_SERIAL_VERSION. If a modification is required, please adjust the getBinaryMetaData
// function. If the modification is made on a custom branch, please change PX_BINARY_SERIAL_VERSION
// accordingly.
//==================================================================================================
public:
/**
\brief the range of the limit. The upper limit must be no lower than the lower limit.
<b>Unit:</b> Angular: Radians
<b>Range:</b> See the joint on which the limit is used for details<br>
<b>Default:</b> lower = -PI/2, upper = PI/2
*/
PxReal upper, lower;
/**
\brief construct an angular hard limit pair.
The lower value must be less than the upper value.
\param[in] lowerLimit The lower angle of the limit
\param[in] upperLimit The upper angle of the limit
\param[in] contactDist The distance from the limit at which it becomes active. Default is the lesser of 0.1 radians, and 0.49 * (upperLimit - lowerLimit)
@see PxJointLimitParameters
*/
PxJointAngularLimitPair(PxReal lowerLimit, PxReal upperLimit, PxReal contactDist = -1.0f) :
upper(upperLimit),
lower(lowerLimit)
{
PxJointLimitParameters::contactDistance = contactDist ==-1.0f ? PxMin(0.1f, 0.49f*(upperLimit-lowerLimit)) : contactDist;
bounceThreshold = 0.5f;
}
/**
\brief construct an angular soft limit pair.
The lower value must be less than the upper value.
\param[in] lowerLimit The lower angle of the limit
\param[in] upperLimit The upper angle of the limit
\param[in] spring The stiffness and damping of the limit spring
@see PxJointLimitParameters
*/
PxJointAngularLimitPair(PxReal lowerLimit, PxReal upperLimit, const PxSpring& spring) :
upper(upperLimit),
lower(lowerLimit)
{
stiffness = spring.stiffness;
damping = spring.damping;
}
/**
\brief Returns true if the limit is valid.
\return true if the current settings are valid
*/
PX_INLINE bool isValid() const
{
return PxJointLimitParameters::isValid() &&
PxIsFinite(upper) && PxIsFinite(lower) && upper >= lower;
}
};
/**
\brief Describes an elliptical conical joint limit. Note that very small or highly elliptical limit cones may
result in jitter.
@see PxD6Joint PxSphericalJoint
*/
class PxJointLimitCone : public PxJointLimitParameters
{
//= ATTENTION! =====================================================================================
// Changing the data layout of this class breaks the binary serialization format. See comments for
// PX_BINARY_SERIAL_VERSION. If a modification is required, please adjust the getBinaryMetaData
// function. If the modification is made on a custom branch, please change PX_BINARY_SERIAL_VERSION
// accordingly.
//==================================================================================================
public:
/**
\brief the maximum angle from the Y axis of the constraint frame.
<b>Unit:</b> Angular: Radians
<b>Range:</b> Angular: (0,PI)<br>
<b>Default:</b> PI/2
*/
PxReal yAngle;
/**
\brief the maximum angle from the Z-axis of the constraint frame.
<b>Unit:</b> Angular: Radians
<b>Range:</b> Angular: (0,PI)<br>
<b>Default:</b> PI/2
*/
PxReal zAngle;
/**
\brief Construct a cone hard limit.
\param[in] yLimitAngle The limit angle from the Y-axis of the constraint frame
\param[in] zLimitAngle The limit angle from the Z-axis of the constraint frame
\param[in] contactDist The distance from the limit at which it becomes active. Default is the lesser of 0.1 radians, and 0.49 * the lower of the limit angles
@see PxJointLimitParameters
*/
PxJointLimitCone(PxReal yLimitAngle, PxReal zLimitAngle, PxReal contactDist = -1.0f) :
yAngle(yLimitAngle),
zAngle(zLimitAngle)
{
PxJointLimitParameters::contactDistance = contactDist == -1.0f ? PxMin(0.1f, PxMin(yLimitAngle, zLimitAngle)*0.49f) : contactDist;
bounceThreshold = 0.5f;
}
/**
\brief Construct a cone soft limit.
\param[in] yLimitAngle The limit angle from the Y-axis of the constraint frame
\param[in] zLimitAngle The limit angle from the Z-axis of the constraint frame
\param[in] spring The stiffness and damping of the limit spring
@see PxJointLimitParameters
*/
PxJointLimitCone(PxReal yLimitAngle, PxReal zLimitAngle, const PxSpring& spring) :
yAngle(yLimitAngle),
zAngle(zLimitAngle)
{
stiffness = spring.stiffness;
damping = spring.damping;
}
/**
\brief Returns true if the limit is valid.
\return true if the current settings are valid
*/
PX_INLINE bool isValid() const
{
return PxJointLimitParameters::isValid() &&
PxIsFinite(yAngle) && yAngle>0 && yAngle<PxPi &&
PxIsFinite(zAngle) && zAngle>0 && zAngle<PxPi;
}
};
/**
\brief Describes a pyramidal joint limit.
@see PxD6Joint
*/
class PxJointLimitPyramid : public PxJointLimitParameters
{
//= ATTENTION! =====================================================================================
// Changing the data layout of this class breaks the binary serialization format. See comments for
// PX_BINARY_SERIAL_VERSION. If a modification is required, please adjust the getBinaryMetaData
// function. If the modification is made on a custom branch, please change PX_BINARY_SERIAL_VERSION
// accordingly.
//==================================================================================================
public:
/**
\brief the minimum angle from the Y axis of the constraint frame.
<b>Unit:</b> Angular: Radians
<b>Range:</b> Angular: (-PI,PI)<br>
<b>Default:</b> -PI/2
*/
PxReal yAngleMin;
/**
\brief the maximum angle from the Y axis of the constraint frame.
<b>Unit:</b> Angular: Radians
<b>Range:</b> Angular: (-PI,PI)<br>
<b>Default:</b> PI/2
*/
PxReal yAngleMax;
/**
\brief the minimum angle from the Z-axis of the constraint frame.
<b>Unit:</b> Angular: Radians
<b>Range:</b> Angular: (-PI,PI)<br>
<b>Default:</b> -PI/2
*/
PxReal zAngleMin;
/**
\brief the maximum angle from the Z-axis of the constraint frame.
<b>Unit:</b> Angular: Radians
<b>Range:</b> Angular: (-PI,PI)<br>
<b>Default:</b> PI/2
*/
PxReal zAngleMax;
/**
\brief Construct a pyramid hard limit.
\param[in] yLimitAngleMin The minimum limit angle from the Y-axis of the constraint frame
\param[in] yLimitAngleMax The maximum limit angle from the Y-axis of the constraint frame
\param[in] zLimitAngleMin The minimum limit angle from the Z-axis of the constraint frame
\param[in] zLimitAngleMax The maximum limit angle from the Z-axis of the constraint frame
\param[in] contactDist The distance from the limit at which it becomes active. Default is the lesser of 0.1 radians, and 0.49 * the lower of the limit angles
@see PxJointLimitParameters
*/
PxJointLimitPyramid(PxReal yLimitAngleMin, PxReal yLimitAngleMax, PxReal zLimitAngleMin, PxReal zLimitAngleMax, PxReal contactDist = -1.0f) :
yAngleMin(yLimitAngleMin),
yAngleMax(yLimitAngleMax),
zAngleMin(zLimitAngleMin),
zAngleMax(zLimitAngleMax)
{
if(contactDist == -1.0f)
{
const PxReal contactDistY = PxMin(0.1f, 0.49f*(yLimitAngleMax - yLimitAngleMin));
const PxReal contactDistZ = PxMin(0.1f, 0.49f*(zLimitAngleMax - zLimitAngleMin));
PxJointLimitParameters::contactDistance = contactDist == PxMin(contactDistY, contactDistZ);
}
else
{
PxJointLimitParameters::contactDistance = contactDist;
}
bounceThreshold = 0.5f;
}
/**
\brief Construct a pyramid soft limit.
\param[in] yLimitAngleMin The minimum limit angle from the Y-axis of the constraint frame
\param[in] yLimitAngleMax The maximum limit angle from the Y-axis of the constraint frame
\param[in] zLimitAngleMin The minimum limit angle from the Z-axis of the constraint frame
\param[in] zLimitAngleMax The maximum limit angle from the Z-axis of the constraint frame
\param[in] spring The stiffness and damping of the limit spring
@see PxJointLimitParameters
*/
PxJointLimitPyramid(PxReal yLimitAngleMin, PxReal yLimitAngleMax, PxReal zLimitAngleMin, PxReal zLimitAngleMax, const PxSpring& spring) :
yAngleMin(yLimitAngleMin),
yAngleMax(yLimitAngleMax),
zAngleMin(zLimitAngleMin),
zAngleMax(zLimitAngleMax)
{
stiffness = spring.stiffness;
damping = spring.damping;
}
/**
\brief Returns true if the limit is valid.
\return true if the current settings are valid
*/
PX_INLINE bool isValid() const
{
return PxJointLimitParameters::isValid() &&
PxIsFinite(yAngleMin) && yAngleMin>-PxPi && yAngleMin<PxPi &&
PxIsFinite(yAngleMax) && yAngleMax>-PxPi && yAngleMax<PxPi &&
PxIsFinite(zAngleMin) && zAngleMin>-PxPi && zAngleMin<PxPi &&
PxIsFinite(zAngleMax) && zAngleMax>-PxPi && zAngleMax<PxPi &&
yAngleMax>=yAngleMin && zAngleMax>=zAngleMin;
}
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,334 @@
//
// 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-2018 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_EXTENSIONS_MASS_PROPERTIES_H
#define PX_PHYSICS_EXTENSIONS_MASS_PROPERTIES_H
/** \addtogroup extensions
@{
*/
#include "PxPhysXConfig.h"
#include "foundation/PxMath.h"
#include "foundation/PxMathUtils.h"
#include "foundation/PxVec3.h"
#include "foundation/PxMat33.h"
#include "foundation/PxQuat.h"
#include "foundation/PxTransform.h"
#include "geometry/PxGeometry.h"
#include "geometry/PxBoxGeometry.h"
#include "geometry/PxSphereGeometry.h"
#include "geometry/PxCapsuleGeometry.h"
#include "geometry/PxConvexMeshGeometry.h"
#include "geometry/PxConvexMesh.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
/**
\brief Utility class to compute and manipulate mass and inertia tensor properties.
In most cases #PxRigidBodyExt::updateMassAndInertia(), #PxRigidBodyExt::setMassAndUpdateInertia() should be enough to
setup the mass properties of a rigid body. This utility class targets users that need to customize the mass properties
computation.
*/
class PxMassProperties
{
public:
/**
\brief Default constructor.
*/
PX_FORCE_INLINE PxMassProperties() : inertiaTensor(PxIdentity), centerOfMass(0.0f), mass(1.0f) {}
/**
\brief Construct from individual elements.
*/
PX_FORCE_INLINE PxMassProperties(const PxReal m, const PxMat33& inertiaT, const PxVec3& com) : inertiaTensor(inertiaT), centerOfMass(com), mass(m) {}
/**
\brief Compute mass properties based on a provided geometry structure.
This constructor assumes the geometry has a density of 1. Mass and inertia tensor scale linearly with density.
\param[in] geometry The geometry to compute the mass properties for. Supported geometry types are: sphere, box, capsule and convex mesh.
*/
PxMassProperties(const PxGeometry& geometry)
{
switch (geometry.getType())
{
case PxGeometryType::eSPHERE:
{
const PxSphereGeometry& s = static_cast<const PxSphereGeometry&>(geometry);
mass = (4.0f / 3.0f) * PxPi * s.radius * s.radius * s.radius;
inertiaTensor = PxMat33::createDiagonal(PxVec3(2.0f / 5.0f * mass * s.radius * s.radius));
centerOfMass = PxVec3(0.0f);
}
break;
case PxGeometryType::eBOX:
{
const PxBoxGeometry& b = static_cast<const PxBoxGeometry&>(geometry);
mass = b.halfExtents.x * b.halfExtents.y * b.halfExtents.z * 8.0f;
PxVec3 d2 = b.halfExtents.multiply(b.halfExtents);
inertiaTensor = PxMat33::createDiagonal(PxVec3(d2.y + d2.z, d2.x + d2.z, d2.x + d2.y)) * (mass * 1.0f / 3.0f);
centerOfMass = PxVec3(0.0f);
}
break;
case PxGeometryType::eCAPSULE:
{
const PxCapsuleGeometry& c = static_cast<const PxCapsuleGeometry&>(geometry);
PxReal r = c.radius, h = c.halfHeight;
mass = ((4.0f / 3.0f) * r + 2 * c.halfHeight) * PxPi * r * r;
PxReal a = r*r*r * (8.0f / 15.0f) + h*r*r * (3.0f / 2.0f) + h*h*r * (4.0f / 3.0f) + h*h*h * (2.0f / 3.0f);
PxReal b = r*r*r * (8.0f / 15.0f) + h*r*r;
inertiaTensor = PxMat33::createDiagonal(PxVec3(b, a, a) * PxPi * r * r);
centerOfMass = PxVec3(0.0f);
}
break;
case PxGeometryType::eCONVEXMESH:
{
const PxConvexMeshGeometry& c = static_cast<const PxConvexMeshGeometry&>(geometry);
PxVec3 unscaledCoM;
PxMat33 unscaledInertiaTensorNonCOM; // inertia tensor of convex mesh in mesh local space
PxMat33 unscaledInertiaTensorCOM;
PxReal unscaledMass;
c.convexMesh->getMassInformation(unscaledMass, unscaledInertiaTensorNonCOM, unscaledCoM);
// inertia tensor relative to center of mass
unscaledInertiaTensorCOM[0][0] = unscaledInertiaTensorNonCOM[0][0] - unscaledMass*PxReal((unscaledCoM.y*unscaledCoM.y+unscaledCoM.z*unscaledCoM.z));
unscaledInertiaTensorCOM[1][1] = unscaledInertiaTensorNonCOM[1][1] - unscaledMass*PxReal((unscaledCoM.z*unscaledCoM.z+unscaledCoM.x*unscaledCoM.x));
unscaledInertiaTensorCOM[2][2] = unscaledInertiaTensorNonCOM[2][2] - unscaledMass*PxReal((unscaledCoM.x*unscaledCoM.x+unscaledCoM.y*unscaledCoM.y));
unscaledInertiaTensorCOM[0][1] = unscaledInertiaTensorCOM[1][0] = (unscaledInertiaTensorNonCOM[0][1] + unscaledMass*PxReal(unscaledCoM.x*unscaledCoM.y));
unscaledInertiaTensorCOM[1][2] = unscaledInertiaTensorCOM[2][1] = (unscaledInertiaTensorNonCOM[1][2] + unscaledMass*PxReal(unscaledCoM.y*unscaledCoM.z));
unscaledInertiaTensorCOM[0][2] = unscaledInertiaTensorCOM[2][0] = (unscaledInertiaTensorNonCOM[0][2] + unscaledMass*PxReal(unscaledCoM.z*unscaledCoM.x));
const PxMeshScale& s = c.scale;
mass = unscaledMass * s.scale.x * s.scale.y * s.scale.z;
centerOfMass = s.rotation.rotate(s.scale.multiply(s.rotation.rotateInv(unscaledCoM)));
inertiaTensor = scaleInertia(unscaledInertiaTensorCOM, s.rotation, s.scale);
}
break;
case PxGeometryType::eHEIGHTFIELD:
case PxGeometryType::ePLANE:
case PxGeometryType::eTRIANGLEMESH:
case PxGeometryType::eINVALID:
case PxGeometryType::eGEOMETRY_COUNT:
{
*this = PxMassProperties();
}
break;
}
PX_ASSERT(inertiaTensor.column0.isFinite() && inertiaTensor.column1.isFinite() && inertiaTensor.column2.isFinite());
PX_ASSERT(centerOfMass.isFinite());
PX_ASSERT(PxIsFinite(mass));
}
/**
\brief Scale mass properties.
\param[in] scale The linear scaling factor to apply to the mass properties.
\return The scaled mass properties.
*/
PX_FORCE_INLINE PxMassProperties operator*(const PxReal scale) const
{
PX_ASSERT(PxIsFinite(scale));
return PxMassProperties(mass * scale, inertiaTensor * scale, centerOfMass);
}
/**
\brief Translate the center of mass by a given vector and adjust the inertia tensor accordingly.
\param[in] t The translation vector for the center of mass.
*/
PX_FORCE_INLINE void translate(const PxVec3& t)
{
PX_ASSERT(t.isFinite());
inertiaTensor = translateInertia(inertiaTensor, mass, t);
centerOfMass += t;
PX_ASSERT(inertiaTensor.column0.isFinite() && inertiaTensor.column1.isFinite() && inertiaTensor.column2.isFinite());
PX_ASSERT(centerOfMass.isFinite());
}
/**
\brief Get the entries of the diagonalized inertia tensor and the corresponding reference rotation.
\param[in] inertia The inertia tensor to diagonalize.
\param[out] massFrame The frame the diagonalized tensor refers to.
\return The entries of the diagonalized inertia tensor.
*/
PX_FORCE_INLINE static PxVec3 getMassSpaceInertia(const PxMat33& inertia, PxQuat& massFrame)
{
PX_ASSERT(inertia.column0.isFinite() && inertia.column1.isFinite() && inertia.column2.isFinite());
PxVec3 diagT = PxDiagonalize(inertia, massFrame);
PX_ASSERT(diagT.isFinite());
PX_ASSERT(massFrame.isFinite());
return diagT;
}
/**
\brief Translate an inertia tensor using the parallel axis theorem
\param[in] inertia The inertia tensor to translate.
\param[in] mass The mass of the object.
\param[in] t The relative frame to translate the inertia tensor to.
\return The translated inertia tensor.
*/
PX_FORCE_INLINE static PxMat33 translateInertia(const PxMat33& inertia, const PxReal mass, const PxVec3& t)
{
PX_ASSERT(inertia.column0.isFinite() && inertia.column1.isFinite() && inertia.column2.isFinite());
PX_ASSERT(PxIsFinite(mass));
PX_ASSERT(t.isFinite());
PxMat33 s( PxVec3(0,t.z,-t.y),
PxVec3(-t.z,0,t.x),
PxVec3(t.y,-t.x,0) );
PxMat33 translatedIT = s.getTranspose() * s * mass + inertia;
PX_ASSERT(translatedIT.column0.isFinite() && translatedIT.column1.isFinite() && translatedIT.column2.isFinite());
return translatedIT;
}
/**
\brief Rotate an inertia tensor around the center of mass
\param[in] inertia The inertia tensor to rotate.
\param[in] q The rotation to apply to the inertia tensor.
\return The rotated inertia tensor.
*/
PX_FORCE_INLINE static PxMat33 rotateInertia(const PxMat33& inertia, const PxQuat& q)
{
PX_ASSERT(inertia.column0.isFinite() && inertia.column1.isFinite() && inertia.column2.isFinite());
PX_ASSERT(q.isUnit());
PxMat33 m(q);
PxMat33 rotatedIT = m * inertia * m.getTranspose();
PX_ASSERT(rotatedIT.column0.isFinite() && rotatedIT.column1.isFinite() && rotatedIT.column2.isFinite());
return rotatedIT;
}
/**
\brief Non-uniform scaling of the inertia tensor
\param[in] inertia The inertia tensor to scale.
\param[in] scaleRotation The frame of the provided scaling factors.
\param[in] scale The scaling factor for each axis (relative to the frame specified in scaleRotation).
\return The scaled inertia tensor.
*/
static PxMat33 scaleInertia(const PxMat33& inertia, const PxQuat& scaleRotation, const PxVec3& scale)
{
PX_ASSERT(inertia.column0.isFinite() && inertia.column1.isFinite() && inertia.column2.isFinite());
PX_ASSERT(scaleRotation.isUnit());
PX_ASSERT(scale.isFinite());
PxMat33 localInertiaT = rotateInertia(inertia, scaleRotation); // rotate inertia into scaling frame
PxVec3 diagonal(localInertiaT[0][0], localInertiaT[1][1], localInertiaT[2][2]);
PxVec3 xyz2 = PxVec3(diagonal.dot(PxVec3(0.5f))) - diagonal; // original x^2, y^2, z^2
PxVec3 scaledxyz2 = xyz2.multiply(scale).multiply(scale);
PxReal xx = scaledxyz2.y + scaledxyz2.z,
yy = scaledxyz2.z + scaledxyz2.x,
zz = scaledxyz2.x + scaledxyz2.y;
PxReal xy = localInertiaT[0][1] * scale.x * scale.y,
xz = localInertiaT[0][2] * scale.x * scale.z,
yz = localInertiaT[1][2] * scale.y * scale.z;
PxMat33 scaledInertia( PxVec3(xx, xy, xz),
PxVec3(xy, yy, yz),
PxVec3(xz, yz, zz));
PxMat33 scaledIT = rotateInertia(scaledInertia * (scale.x * scale.y * scale.z), scaleRotation.getConjugate());
PX_ASSERT(scaledIT.column0.isFinite() && scaledIT.column1.isFinite() && scaledIT.column2.isFinite());
return scaledIT;
}
/**
\brief Sum up individual mass properties.
\param[in] props Array of mass properties to sum up.
\param[in] transforms Reference transforms for each mass properties entry.
\param[in] count The number of mass properties to sum up.
\return The summed up mass properties.
*/
static PxMassProperties sum(const PxMassProperties* props, const PxTransform* transforms, const PxU32 count)
{
PxReal combinedMass = 0.0f;
PxVec3 combinedCoM(0.0f);
PxMat33 combinedInertiaT = PxMat33(PxZero);
for(PxU32 i = 0; i < count; i++)
{
PX_ASSERT(props[i].inertiaTensor.column0.isFinite() && props[i].inertiaTensor.column1.isFinite() && props[i].inertiaTensor.column2.isFinite());
PX_ASSERT(props[i].centerOfMass.isFinite());
PX_ASSERT(PxIsFinite(props[i].mass));
combinedMass += props[i].mass;
const PxVec3 comTm = transforms[i].transform(props[i].centerOfMass);
combinedCoM += comTm * props[i].mass;
}
combinedCoM /= combinedMass;
for(PxU32 i = 0; i < count; i++)
{
const PxVec3 comTm = transforms[i].transform(props[i].centerOfMass);
combinedInertiaT += translateInertia(rotateInertia(props[i].inertiaTensor, transforms[i].q), props[i].mass, combinedCoM - comTm);
}
PX_ASSERT(combinedInertiaT.column0.isFinite() && combinedInertiaT.column1.isFinite() && combinedInertiaT.column2.isFinite());
PX_ASSERT(combinedCoM.isFinite());
PX_ASSERT(PxIsFinite(combinedMass));
return PxMassProperties(combinedMass, combinedInertiaT, combinedCoM);
}
PxMat33 inertiaTensor; //!< The inertia tensor of the object.
PxVec3 centerOfMass; //!< The center of mass of the object.
PxReal mass; //!< The mass of the object.
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,236 @@
//
// 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-2018 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_PRISMATICJOINT_H
#define PX_PRISMATICJOINT_H
/** \addtogroup extensions
@{
*/
#include "extensions/PxJoint.h"
#include "extensions/PxJointLimit.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxPrismaticJoint;
/**
\brief Create a prismatic joint.
\param[in] physics The physics SDK
\param[in] actor0 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localFrame0 The position and orientation of the joint relative to actor0
\param[in] actor1 An actor to which the joint is attached. NULL may be used to attach the joint to a specific point in the world frame
\param[in] localFrame1 The position and orientation of the joint relative to actor1
@see PxPrismaticJoint
*/
PxPrismaticJoint* PxPrismaticJointCreate(PxPhysics& physics, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1);
/**
\brief Flags specific to the prismatic joint.
@see PxPrismaticJoint
*/
struct PxPrismaticJointFlag
{
enum Enum
{
eLIMIT_ENABLED = 1<<1
};
};
typedef PxFlags<PxPrismaticJointFlag::Enum, PxU16> PxPrismaticJointFlags;
PX_FLAGS_OPERATORS(PxPrismaticJointFlag::Enum, PxU16)
/**
\brief A prismatic joint permits relative translational movement between two bodies along
an axis, but no relative rotational movement.
the axis on each body is defined as the line containing the origin of the joint frame and
extending along the x-axis of that frame
\image html prismJoint.png
@see PxPrismaticJointCreate() PxJoint
*/
class PxPrismaticJoint : public PxJoint
{
public:
/**
\brief returns the displacement of the joint along its axis.
*/
virtual PxReal getPosition() const = 0;
/**
\brief returns the velocity of the joint along its axis
*/
virtual PxReal getVelocity() const = 0;
/**
\brief sets the joint limit parameters.
The limit range is [-PX_MAX_F32, PX_MAX_F32], but note that the width of the limit (upper-lower) must also be
a valid float.
@see PxJointLinearLimitPair getLimit()
*/
virtual void setLimit(const PxJointLinearLimitPair&) = 0;
/**
\brief gets the joint limit parameters.
@see PxJointLinearLimit getLimit()
*/
virtual PxJointLinearLimitPair getLimit() const = 0;
/**
\brief Set the flags specific to the Prismatic Joint.
<b>Default</b> PxPrismaticJointFlags(0)
\param[in] flags The joint flags.
@see PxPrismaticJointFlag setFlag() getFlags()
*/
virtual void setPrismaticJointFlags(PxPrismaticJointFlags flags) = 0;
/**
\brief Set a single flag specific to a Prismatic Joint to true or false.
\param[in] flag The flag to set or clear.
\param[in] value The value to which to set the flag
@see PxPrismaticJointFlag, getFlags() setFlags()
*/
virtual void setPrismaticJointFlag(PxPrismaticJointFlag::Enum flag, bool value) = 0;
/**
\brief Get the flags specific to the Prismatic Joint.
\return the joint flags
@see PxPrismaticJoint::flags, PxPrismaticJointFlag setFlag() setFlags()
*/
virtual PxPrismaticJointFlags getPrismaticJointFlags() const = 0;
/**
\brief Set the linear tolerance threshold for projection.
If the joint separates by more than this distance along its locked degrees of freedom, the solver
will move the bodies to close the distance.
Setting a very small tolerance may result in simulation jitter or other artifacts.
Sometimes it is not possible to project (for example when the joints form a cycle).
This value must be nonnegative.
<b>Range:</b> [0, PX_MAX_F32)<br>
<b>Default:</b> 1e10f
\param[in] tolerance the linear tolerance threshold
@see getProjectionLinearTolerance()
*/
virtual void setProjectionLinearTolerance(PxReal tolerance) = 0;
/**
\brief Get the linear tolerance threshold for projection.
\return the linear tolerance threshold in radians
@see setProjectionLinearTolerance()
*/
virtual PxReal getProjectionLinearTolerance() const = 0;
/**
\brief Set the angular tolerance threshold for projection. Projection is enabled if PxConstraintFlag::ePROJECTION
is set for the joint.
If the joint separates by more than this distance along its locked degrees of freedom, the solver
will move the bodies to close the distance.
Setting a very small tolerance may result in simulation jitter or other artifacts.
Sometimes it is not possible to project (for example when the joints form a cycle).
<b>Range:</b> [0, PX_MAX_F32)<br>
<b>Default:</b> Pi
\param[in] tolerance the linear tolerance threshold
@see getProjectionLinearTolerance() PxJoint::setConstraintFlags()
*/
virtual void setProjectionAngularTolerance(PxReal tolerance) = 0;
/**
\brief Get the angular tolerance threshold for projection.
@see getProjectionAngularTolerance()
*/
virtual PxReal getProjectionAngularTolerance() const = 0;
/**
\brief Returns string name of PxPrismaticJoint, used for serialization
*/
virtual const char* getConcreteTypeName() const { return "PxPrismaticJoint"; }
protected:
//serialization
/**
\brief Constructor
*/
PX_INLINE PxPrismaticJoint(PxType concreteType, PxBaseFlags baseFlags) : PxJoint(concreteType, baseFlags) {}
/**
\brief Deserialization constructor
*/
PX_INLINE PxPrismaticJoint(PxBaseFlags baseFlags) : PxJoint(baseFlags) {}
/**
\brief Returns whether a given type name matches with the type of this instance
*/
virtual bool isKindOf(const char* name) const { return !::strcmp("PxPrismaticJoint", name) || PxJoint::isKindOf(name); }
//~serialization
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,100 @@
//
// 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-2018 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_RAYCAST_CCD_H
#define PX_RAYCAST_CCD_H
/** \addtogroup extensions
@{
*/
#include "common/PxPhysXCommonConfig.h"
#include "foundation/PxVec3.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class PxScene;
class PxShape;
class PxRigidDynamic;
class RaycastCCDManagerInternal;
/**
\brief Raycast-CCD manager.
Raycast-CCD is a simple and potentially cheaper alternative to the SDK's built-in continuous collision detection algorithm.
This implementation has some limitations:
- it is only implemented for PxRigidDynamic objects (not for PxArticulationLink)
- it is only implemented for simple actors with 1 shape (not for "compounds")
Also, since it is raycast-based, the solution is not perfect. In particular:
- small dynamic objects can still go through the static world if the ray goes through a crack between edges, or a small
hole in the world (like the keyhole from a door).
- dynamic-vs-dynamic CCD is very approximate. It only works well for fast-moving dynamic objects colliding against
slow-moving dynamic objects.
Finally, since it is using the SDK's scene queries under the hood, it only works provided the simulation shapes also have
scene-query shapes associated with them. That is, if the objects in the scene only use PxShapeFlag::eSIMULATION_SHAPE
(and no PxShapeFlag::eSCENE_QUERY_SHAPE), then the raycast-CCD system will not work.
*/
class RaycastCCDManager
{
public:
RaycastCCDManager(PxScene* scene);
~RaycastCCDManager();
/**
\brief Register dynamic object for raycast CCD.
\param[in] actor object's actor
\param[in] shape object's shape
\return True if success
*/
bool registerRaycastCCDObject(PxRigidDynamic* actor, PxShape* shape);
/**
\brief Perform raycast CCD. Call this after your simulate/fetchResults calls.
\param[in] doDynamicDynamicCCD True to enable dynamic-vs-dynamic CCD (more expensive, not always needed)
*/
void doRaycastCCD(bool doDynamicDynamicCCD);
private:
RaycastCCDManagerInternal* mImpl;
};
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

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