include/PxArticulationReducedCoordinate.h
File members: include/PxArticulationReducedCoordinate.h
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of NVIDIA CORPORATION nor the names of its
// contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY
// EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
// PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
// CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
// EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
// PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
// OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
// Copyright (c) 2008-2023 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#ifndef PX_ARTICULATION_RC_H
#define PX_ARTICULATION_RC_H
#include "PxPhysXConfig.h"
#include "common/PxBase.h"
#include "foundation/PxVec3.h"
#include "foundation/PxTransform.h"
#include "solver/PxSolverDefs.h"
#include "PxArticulationFlag.h"
#include "PxArticulationTendon.h"
#include "PxArticulationFlag.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
PX_ALIGN_PREFIX(16)
struct PxSpatialForce
{
PxVec3 force;
PxReal pad0;
PxVec3 torque;
PxReal pad1;
}
PX_ALIGN_SUFFIX(16);
PX_ALIGN_PREFIX(16)
struct PxSpatialVelocity
{
PxVec3 linear;
PxReal pad0;
PxVec3 angular;
PxReal pad1;
}
PX_ALIGN_SUFFIX(16);
class PxConstraint;
class PxScene;
struct PxArticulationRootLinkData
{
PxTransform transform;
// The velocities and accelerations below are with respect to the center of mass (COM) of the root link. The COM and actor frame origin may not coincide.
PxVec3 worldLinVel;
PxVec3 worldAngVel;
PxVec3 worldLinAccel;
PxVec3 worldAngAccel;
};
class PxArticulationCache
{
public:
PxArticulationCache() :
externalForces (NULL),
denseJacobian (NULL),
massMatrix (NULL),
jointVelocity (NULL),
jointAcceleration (NULL),
jointPosition (NULL),
jointForce (NULL),
jointSolverForces (NULL),
jointTargetPositions (NULL),
jointTargetVelocities (NULL),
linkVelocity (NULL),
linkAcceleration (NULL),
linkIncomingJointForce (NULL),
rootLinkData (NULL),
sensorForces (NULL),
coefficientMatrix (NULL),
lambda (NULL),
scratchMemory (NULL),
scratchAllocator (NULL),
version (0)
{}
PX_PHYSX_CORE_API void release();
PxSpatialForce* externalForces;
PxReal* denseJacobian;
PxReal* massMatrix;
PxReal* jointVelocity;
PxReal* jointAcceleration;
PxReal* jointPosition;
PxReal* jointForce;
PX_DEPRECATED PxReal* jointSolverForces;
PxReal* jointTargetPositions;
PxReal* jointTargetVelocities;
PxSpatialVelocity* linkVelocity;
PxSpatialVelocity* linkAcceleration;
PxSpatialForce* linkIncomingJointForce;
PxArticulationRootLinkData* rootLinkData;
PX_DEPRECATED PxSpatialForce* sensorForces;
// Members and memory below here are not zeroed when zeroCache is called, and are not included in the size returned by PxArticulationReducedCoordinate::getCacheDataSize.
PxReal* coefficientMatrix;
PxReal* lambda;
void* scratchMemory;
void* scratchAllocator;
PxU32 version;
};
struct PX_DEPRECATED PxArticulationSensorFlag
{
enum Enum
{
eFORWARD_DYNAMICS_FORCES = 1 << 0,
eCONSTRAINT_SOLVER_FORCES = 1 << 1,
eWORLD_FRAME = 1 << 2
};
};
typedef PX_DEPRECATED physx::PxFlags<PxArticulationSensorFlag::Enum, PxU8> PxArticulationSensorFlags;
class PX_DEPRECATED PxArticulationSensor : public PxBase
{
public:
virtual void release() = 0;
virtual PxSpatialForce getForces() const = 0;
virtual PxTransform getRelativePose() const = 0;
virtual void setRelativePose(const PxTransform& pose) = 0;
virtual PxArticulationLink* getLink() const = 0;
virtual PxU32 getIndex() const = 0;
virtual PxArticulationReducedCoordinate* getArticulation() const = 0;
virtual PxArticulationSensorFlags getFlags() const = 0;
virtual void setFlag(PxArticulationSensorFlag::Enum flag, bool enabled) = 0;
virtual const char* getConcreteTypeName() const { return "PxArticulationSensor"; }
virtual ~PxArticulationSensor() {}
void* userData;
protected:
PX_INLINE PxArticulationSensor(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags) {}
PX_INLINE PxArticulationSensor(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
};
struct PxArticulationKinematicFlag
{
enum Enum
{
ePOSITION = 1 << 0,
eVELOCITY = 1 << 1
};
};
typedef physx::PxFlags<PxArticulationKinematicFlag::Enum, PxU8> PxArticulationKinematicFlags;
PX_FLAGS_OPERATORS(PxArticulationKinematicFlag::Enum, PxU8)
#if PX_VC
#pragma warning(push)
#pragma warning(disable : 4435)
#endif
class PxArticulationReducedCoordinate : public PxBase
{
public:
virtual PxScene* getScene() const = 0;
virtual void setSolverIterationCounts(PxU32 minPositionIters, PxU32 minVelocityIters = 1) = 0;
virtual void getSolverIterationCounts(PxU32& minPositionIters, PxU32& minVelocityIters) const = 0;
virtual bool isSleeping() const = 0;
virtual void setSleepThreshold(PxReal threshold) = 0;
virtual PxReal getSleepThreshold() const = 0;
virtual void setStabilizationThreshold(PxReal threshold) = 0;
virtual PxReal getStabilizationThreshold() const = 0;
virtual void setWakeCounter(PxReal wakeCounterValue) = 0;
virtual PxReal getWakeCounter() const = 0;
virtual void wakeUp() = 0;
virtual void putToSleep() = 0;
PX_DEPRECATED virtual void setMaxCOMLinearVelocity(const PxReal maxLinearVelocity) = 0;
PX_DEPRECATED virtual PxReal getMaxCOMLinearVelocity() const = 0;
PX_DEPRECATED virtual void setMaxCOMAngularVelocity(const PxReal maxAngularVelocity) = 0;
PX_DEPRECATED virtual PxReal getMaxCOMAngularVelocity() const = 0;
virtual PxArticulationLink* createLink(PxArticulationLink* parent, const PxTransform& pose) = 0;
virtual void release() = 0;
virtual PxU32 getNbLinks() const = 0;
virtual PxU32 getLinks(PxArticulationLink** userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0;
virtual PxU32 getNbShapes() const = 0;
virtual void setName(const char* name) = 0;
virtual const char* getName() const = 0;
virtual PxBounds3 getWorldBounds(float inflation = 1.01f) const = 0;
virtual PxAggregate* getAggregate() const = 0;
virtual void setArticulationFlags(PxArticulationFlags flags) = 0;
virtual void setArticulationFlag(PxArticulationFlag::Enum flag, bool value) = 0;
virtual PxArticulationFlags getArticulationFlags() const = 0;
virtual PxU32 getDofs() const = 0;
virtual PxArticulationCache* createCache() const = 0;
virtual PxU32 getCacheDataSize() const = 0;
virtual void zeroCache(PxArticulationCache& cache) const = 0;
virtual void applyCache(PxArticulationCache& cache, const PxArticulationCacheFlags flags, bool autowake = true) = 0;
virtual void copyInternalStateToCache(PxArticulationCache& cache, const PxArticulationCacheFlags flags) const = 0;
virtual void packJointData(const PxReal* maximum, PxReal* reduced) const = 0;
virtual void unpackJointData(const PxReal* reduced, PxReal* maximum) const = 0;
virtual void commonInit() const = 0;
virtual void computeGeneralizedGravityForce(PxArticulationCache& cache) const = 0;
virtual void computeCoriolisAndCentrifugalForce(PxArticulationCache& cache) const = 0;
virtual void computeGeneralizedExternalForce(PxArticulationCache& cache) const = 0;
virtual void computeJointAcceleration(PxArticulationCache& cache) const = 0;
virtual void computeJointForce(PxArticulationCache& cache) const = 0;
virtual void computeDenseJacobian(PxArticulationCache& cache, PxU32& nRows, PxU32& nCols) const = 0;
virtual void computeCoefficientMatrix(PxArticulationCache& cache) const = 0;
virtual bool computeLambda(PxArticulationCache& cache, PxArticulationCache& initialState, const PxReal* const jointTorque, const PxU32 maxIter) const = 0;
virtual void computeGeneralizedMassMatrix(PxArticulationCache& cache) const = 0;
virtual void addLoopJoint(PxConstraint* joint) = 0;
virtual void removeLoopJoint(PxConstraint* joint) = 0;
virtual PxU32 getNbLoopJoints() const = 0;
virtual PxU32 getLoopJoints(PxConstraint** userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0;
virtual PxU32 getCoefficientMatrixSize() const = 0;
virtual void setRootGlobalPose(const PxTransform& pose, bool autowake = true) = 0;
virtual PxTransform getRootGlobalPose() const = 0;
virtual void setRootLinearVelocity(const PxVec3& linearVelocity, bool autowake = true) = 0;
virtual PxVec3 getRootLinearVelocity(void) const = 0;
virtual void setRootAngularVelocity(const PxVec3& angularVelocity, bool autowake = true) = 0;
virtual PxVec3 getRootAngularVelocity(void) const = 0;
virtual PxSpatialVelocity getLinkAcceleration(const PxU32 linkId) = 0;
virtual PxU32 getGpuArticulationIndex() = 0;
virtual PxArticulationSpatialTendon* createSpatialTendon() = 0;
virtual PxArticulationFixedTendon* createFixedTendon() = 0;
virtual PX_DEPRECATED PxArticulationSensor* createSensor(PxArticulationLink* link, const PxTransform& relativePose) = 0;
virtual PxU32 getSpatialTendons(PxArticulationSpatialTendon** userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0;
virtual PxU32 getNbSpatialTendons() = 0;
virtual PxU32 getFixedTendons(PxArticulationFixedTendon** userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0;
virtual PxU32 getNbFixedTendons() = 0;
virtual PX_DEPRECATED PxU32 getSensors(PxArticulationSensor** userBuffer, PxU32 bufferSize, PxU32 startIndex = 0) const = 0;
virtual PX_DEPRECATED PxU32 getNbSensors() = 0;
virtual void updateKinematic(PxArticulationKinematicFlags flags) = 0;
virtual ~PxArticulationReducedCoordinate() {}
void* userData;
protected:
PX_INLINE PxArticulationReducedCoordinate(PxType concreteType, PxBaseFlags baseFlags) : PxBase(concreteType, baseFlags) {}
PX_INLINE PxArticulationReducedCoordinate(PxBaseFlags baseFlags) : PxBase(baseFlags) {}
};
#if PX_VC
#pragma warning(pop)
#endif
#if !PX_DOXYGEN
} // namespace physx
#endif
#endif