This commit is contained in:
2025-11-28 23:13:44 +05:30
commit a3a8e79709
7360 changed files with 1156074 additions and 0 deletions

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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "foundation/PxBounds3.h"
#include "extensions/PxBroadPhaseExt.h"
#include "PsFoundation.h"
#include "CmPhysXCommon.h"
using namespace physx;
PxU32 PxBroadPhaseExt::createRegionsFromWorldBounds(PxBounds3* regions, const PxBounds3& globalBounds, PxU32 nbSubdiv, PxU32 upAxis)
{
PX_CHECK_MSG(globalBounds.isValid(), "PxBroadPhaseExt::createRegionsFromWorldBounds(): invalid bounds provided!");
PX_CHECK_MSG(upAxis<3, "PxBroadPhaseExt::createRegionsFromWorldBounds(): invalid up-axis provided!");
const PxVec3& min = globalBounds.minimum;
const PxVec3& max = globalBounds.maximum;
const float dx = (max.x - min.x) / float(nbSubdiv);
const float dy = (max.y - min.y) / float(nbSubdiv);
const float dz = (max.z - min.z) / float(nbSubdiv);
PxU32 nbRegions = 0;
PxVec3 currentMin, currentMax;
for(PxU32 j=0;j<nbSubdiv;j++)
{
for(PxU32 i=0;i<nbSubdiv;i++)
{
if(upAxis==0)
{
currentMin = PxVec3(min.x, min.y + dy * float(i), min.z + dz * float(j));
currentMax = PxVec3(max.x, min.y + dy * float(i+1), min.z + dz * float(j+1));
}
else if(upAxis==1)
{
currentMin = PxVec3(min.x + dx * float(i), min.y, min.z + dz * float(j));
currentMax = PxVec3(min.x + dx * float(i+1), max.y, min.z + dz * float(j+1));
}
else if(upAxis==2)
{
currentMin = PxVec3(min.x + dx * float(i), min.y + dy * float(j), min.z);
currentMax = PxVec3(min.x + dx * float(i+1), min.y + dy * float(j+1), max.z);
}
regions[nbRegions++] = PxBounds3(currentMin, currentMax);
}
}
return nbRegions;
}

View File

@ -0,0 +1,233 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "common/PxBase.h"
#include "geometry/PxConvexMesh.h"
#include "geometry/PxTriangleMesh.h"
#include "geometry/PxHeightField.h"
#include "extensions/PxJoint.h"
#include "extensions/PxConstraintExt.h"
#include "extensions/PxCollectionExt.h"
#include "PxShape.h"
#include "PxMaterial.h"
#include "PxArticulation.h"
#include "PxAggregate.h"
#include "PxPhysics.h"
#include "PxScene.h"
#include "PxPruningStructure.h"
#include "PsArray.h"
using namespace physx;
void PxCollectionExt::releaseObjects(PxCollection& collection, bool releaseExclusiveShapes)
{
shdfnd::Array<PxBase*> releasableObjects;
for (PxU32 i = 0; i < collection.getNbObjects(); ++i)
{
PxBase* s = &collection.getObject(i);
// pruning structure must be released before its actors
if(s->is<PxPruningStructure>())
{
if(!releasableObjects.empty())
{
PxBase* first = releasableObjects[0];
releasableObjects.pushBack(first);
releasableObjects[0] = s;
}
}
else
{
if (s->isReleasable() && (releaseExclusiveShapes || !s->is<PxShape>() || !s->is<PxShape>()->isExclusive()))
releasableObjects.pushBack(s);
}
}
for (PxU32 i = 0; i < releasableObjects.size(); ++i)
releasableObjects[i]->release();
while (collection.getNbObjects() > 0)
collection.remove(collection.getObject(0));
}
void PxCollectionExt::remove(PxCollection& collection, PxType concreteType, PxCollection* to)
{
shdfnd::Array<PxBase*> removeObjects;
for (PxU32 i = 0; i < collection.getNbObjects(); i++)
{
PxBase& object = collection.getObject(i);
if(concreteType == object.getConcreteType())
{
if(to)
to->add(object);
removeObjects.pushBack(&object);
}
}
for (PxU32 i = 0; i < removeObjects.size(); ++i)
collection.remove(*removeObjects[i]);
}
PxCollection* PxCollectionExt::createCollection(PxPhysics& physics)
{
PxCollection* collection = PxCreateCollection();
if (!collection)
return NULL;
// Collect convexes
{
shdfnd::Array<PxConvexMesh*> objects(physics.getNbConvexMeshes());
const PxU32 nb = physics.getConvexMeshes(objects.begin(), objects.size());
PX_ASSERT(nb == objects.size());
PX_UNUSED(nb);
for(PxU32 i=0;i<objects.size();i++)
collection->add(*objects[i]);
}
// Collect triangle meshes
{
shdfnd::Array<PxTriangleMesh*> objects(physics.getNbTriangleMeshes());
const PxU32 nb = physics.getTriangleMeshes(objects.begin(), objects.size());
PX_ASSERT(nb == objects.size());
PX_UNUSED(nb);
for(PxU32 i=0;i<objects.size();i++)
collection->add(*objects[i]);
}
// Collect heightfields
{
shdfnd::Array<PxHeightField*> objects(physics.getNbHeightFields());
const PxU32 nb = physics.getHeightFields(objects.begin(), objects.size());
PX_ASSERT(nb == objects.size());
PX_UNUSED(nb);
for(PxU32 i=0;i<objects.size();i++)
collection->add(*objects[i]);
}
// Collect materials
{
shdfnd::Array<PxMaterial*> objects(physics.getNbMaterials());
const PxU32 nb = physics.getMaterials(objects.begin(), objects.size());
PX_ASSERT(nb == objects.size());
PX_UNUSED(nb);
for(PxU32 i=0;i<objects.size();i++)
collection->add(*objects[i]);
}
// Collect shapes
{
shdfnd::Array<PxShape*> objects(physics.getNbShapes());
const PxU32 nb = physics.getShapes(objects.begin(), objects.size());
PX_ASSERT(nb == objects.size());
PX_UNUSED(nb);
for(PxU32 i=0;i<objects.size();i++)
collection->add(*objects[i]);
}
return collection;
}
PxCollection* PxCollectionExt::createCollection(PxScene& scene)
{
PxCollection* collection = PxCreateCollection();
if (!collection)
return NULL;
// Collect actors
{
PxActorTypeFlags selectionFlags = PxActorTypeFlag::eRIGID_STATIC | PxActorTypeFlag::eRIGID_DYNAMIC;
shdfnd::Array<PxActor*> objects(scene.getNbActors(selectionFlags));
const PxU32 nb = scene.getActors(selectionFlags, objects.begin(), objects.size());
PX_ASSERT(nb==objects.size());
PX_UNUSED(nb);
for(PxU32 i=0;i<objects.size();i++)
collection->add(*objects[i]);
}
// Collect constraints
{
shdfnd::Array<PxConstraint*> objects(scene.getNbConstraints());
const PxU32 nb = scene.getConstraints(objects.begin(), objects.size());
PX_ASSERT(nb==objects.size());
PX_UNUSED(nb);
for(PxU32 i=0;i<objects.size();i++)
{
PxU32 typeId;
PxJoint* joint = reinterpret_cast<PxJoint*>(objects[i]->getExternalReference(typeId));
if(typeId == PxConstraintExtIDs::eJOINT)
collection->add(*joint);
}
}
// Collect articulations
{
shdfnd::Array<PxArticulationBase*> objects(scene.getNbArticulations());
const PxU32 nb = scene.getArticulations(objects.begin(), objects.size());
PX_ASSERT(nb==objects.size());
PX_UNUSED(nb);
for(PxU32 i=0;i<objects.size();i++)
collection->add(*objects[i]);
}
// Collect aggregates
{
shdfnd::Array<PxAggregate*> objects(scene.getNbAggregates());
const PxU32 nb = scene.getAggregates(objects.begin(), objects.size());
PX_ASSERT(nb==objects.size());
PX_UNUSED(nb);
for(PxU32 i=0;i<objects.size();i++)
collection->add(*objects[i]);
}
return collection;
}

View File

@ -0,0 +1,383 @@
//
// 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-2021 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 NP_CONSTRAINT_HELPER_H
#define NP_CONSTRAINT_HELPER_H
#include "foundation/PxAssert.h"
#include "foundation/PxTransform.h"
#include "foundation/PxMat33.h"
#include "extensions/PxD6Joint.h"
#include "ExtJointData.h"
namespace physx
{
namespace Ext
{
namespace joint
{
PX_INLINE void computeJointFrames(PxTransform& cA2w, PxTransform& cB2w, const JointData& data, const PxTransform& bA2w, const PxTransform& bB2w)
{
PX_ASSERT(bA2w.isValid() && bB2w.isValid());
cA2w = bA2w.transform(data.c2b[0]);
cB2w = bB2w.transform(data.c2b[1]);
PX_ASSERT(cA2w.isValid() && cB2w.isValid());
}
PX_INLINE void computeDerived(const JointData& data,
const PxTransform& bA2w, const PxTransform& bB2w,
PxTransform& cA2w, PxTransform& cB2w, PxTransform& cB2cA,
bool useShortestPath=true)
{
computeJointFrames(cA2w, cB2w, data, bA2w, bB2w);
if(useShortestPath)
{
if(cA2w.q.dot(cB2w.q)<0.0f) // minimum error quat
cB2w.q = -cB2w.q;
}
cB2cA = cA2w.transformInv(cB2w);
PX_ASSERT(cB2cA.isValid());
}
PX_INLINE PxVec3 truncateLinear(const PxVec3& in, PxReal tolerance, bool& truncated)
{
const PxReal m = in.magnitudeSquared();
truncated = m>tolerance * tolerance;
return truncated ? in * PxRecipSqrt(m) * tolerance : in;
}
PX_INLINE PxQuat truncateAngular(const PxQuat& in, PxReal sinHalfTol, PxReal cosHalfTol, bool& truncated)
{
truncated = false;
if(sinHalfTol > 0.9999f) // fixes numerical tolerance issue of projecting because quat is not exactly normalized
return in;
const PxQuat q = in.w>=0.0f ? in : -in;
const PxVec3 im = q.getImaginaryPart();
const PxReal m = im.magnitudeSquared();
truncated = m>sinHalfTol*sinHalfTol;
if(!truncated)
return in;
const PxVec3 outV = im * sinHalfTol * PxRecipSqrt(m);
return PxQuat(outV.x, outV.y, outV.z, cosHalfTol);
}
PX_FORCE_INLINE void projectTransforms(PxTransform& bA2w, PxTransform& bB2w,
const PxTransform& cA2w, const PxTransform& cB2w,
const PxTransform& cB2cA, const JointData& data, bool projectToA)
{
PX_ASSERT(cB2cA.isValid());
// normalization here is unfortunate: long chains of projected constraints can result in
// accumulation of error in the quaternion which eventually leaves the quaternion
// magnitude outside the validation range. The approach here is slightly overconservative
// in that we could just normalize the quaternions which are out of range, but since we
// regard projection as an occasional edge case it shouldn't be perf-sensitive, and
// this way we maintain the invariant (also maintained by the dynamics integrator) that
// body quats are properly normalized up to FP error.
if(projectToA)
{
bB2w = cA2w.transform(cB2cA.transform(data.c2b[1].getInverse()));
bB2w.q.normalize();
}
else
{
bA2w = cB2w.transform(cB2cA.transformInv(data.c2b[0].getInverse()));
bA2w.q.normalize();
}
PX_ASSERT(bA2w.isValid());
PX_ASSERT(bB2w.isValid());
}
PX_INLINE void computeJacobianAxes(PxVec3 row[3], const PxQuat& qa, const PxQuat& qb)
{
// Compute jacobian matrix for (qa* qb) [[* means conjugate in this expr]]
// d/dt (qa* qb) = 1/2 L(qa*) R(qb) (omega_b - omega_a)
// result is L(qa*) R(qb), where L(q) and R(q) are left/right q multiply matrix
const PxReal wa = qa.w, wb = qb.w;
const PxVec3 va(qa.x,qa.y,qa.z), vb(qb.x,qb.y,qb.z);
const PxVec3 c = vb*wa + va*wb;
const PxReal d0 = wa*wb;
const PxReal d1 = va.dot(vb);
const PxReal d = d0 - d1;
row[0] = (va * vb.x + vb * va.x + PxVec3(d, c.z, -c.y)) * 0.5f;
row[1] = (va * vb.y + vb * va.y + PxVec3(-c.z, d, c.x)) * 0.5f;
row[2] = (va * vb.z + vb * va.z + PxVec3(c.y, -c.x, d)) * 0.5f;
if((d0 + d1) != 0.0f) // check if relative rotation is 180 degrees which can lead to singular matrix
return;
else
{
row[0].x += PX_EPS_F32;
row[1].y += PX_EPS_F32;
row[2].z += PX_EPS_F32;
}
}
PX_FORCE_INLINE Px1DConstraint* _linear(const PxVec3& axis, const PxVec3& ra, const PxVec3& rb, PxReal posErr, PxConstraintSolveHint::Enum hint, Px1DConstraint* c)
{
c->solveHint = PxU16(hint);
c->linear0 = axis;
c->angular0 = ra.cross(axis);
c->linear1 = axis;
c->angular1 = rb.cross(axis);
c->geometricError = posErr;
PX_ASSERT(c->linear0.isFinite());
PX_ASSERT(c->linear1.isFinite());
PX_ASSERT(c->angular0.isFinite());
PX_ASSERT(c->angular1.isFinite());
return c;
}
PX_FORCE_INLINE Px1DConstraint* _angular(const PxVec3& axis, PxReal posErr, PxConstraintSolveHint::Enum hint, Px1DConstraint* c)
{
c->solveHint = PxU16(hint);
c->linear0 = PxVec3(0.0f);
c->angular0 = axis;
c->linear1 = PxVec3(0.0f);
c->angular1 = axis;
c->geometricError = posErr;
c->flags |= Px1DConstraintFlag::eANGULAR_CONSTRAINT;
return c;
}
class ConstraintHelper
{
Px1DConstraint* mConstraints;
Px1DConstraint* mCurrent;
PxVec3 mRa, mRb;
PxVec3 mCA2w, mCB2w;
public:
ConstraintHelper(Px1DConstraint* c, const PxVec3& ra, const PxVec3& rb)
: mConstraints(c), mCurrent(c), mRa(ra), mRb(rb) {}
ConstraintHelper(Px1DConstraint* c, PxConstraintInvMassScale& invMassScale,
PxTransform& cA2w, PxTransform& cB2w, PxVec3& body0WorldOffset,
const JointData& data, const PxTransform& bA2w, const PxTransform& bB2w)
: mConstraints(c), mCurrent(c)
{
invMassScale = data.invMassScale;
computeJointFrames(cA2w, cB2w, data, bA2w, bB2w);
body0WorldOffset = cB2w.p - bA2w.p;
mRa = cB2w.p - bA2w.p;
mRb = cB2w.p - bB2w.p;
mCA2w = cA2w.p;
mCB2w = cB2w.p;
}
PX_FORCE_INLINE const PxVec3& getRa() const { return mRa; }
PX_FORCE_INLINE const PxVec3& getRb() const { return mRb; }
// hard linear & angular
PX_FORCE_INLINE void linearHard(const PxVec3& axis, PxReal posErr)
{
Px1DConstraint* c = linear(axis, posErr, PxConstraintSolveHint::eEQUALITY);
c->flags |= Px1DConstraintFlag::eOUTPUT_FORCE;
}
PX_FORCE_INLINE void angularHard(const PxVec3& axis, PxReal posErr)
{
Px1DConstraint* c = angular(axis, posErr, PxConstraintSolveHint::eEQUALITY);
c->flags |= Px1DConstraintFlag::eOUTPUT_FORCE;
}
// limited linear & angular
PX_FORCE_INLINE void linearLimit(const PxVec3& axis, PxReal ordinate, PxReal limitValue, const PxJointLimitParameters& limit)
{
const PxReal pad = limit.isSoft() ? 0.0f : limit.contactDistance;
if(ordinate + pad > limitValue)
addLimit(linear(axis, limitValue - ordinate, PxConstraintSolveHint::eNONE), limit);
}
PX_FORCE_INLINE void angularLimit(const PxVec3& axis, PxReal ordinate, PxReal limitValue, PxReal pad, const PxJointLimitParameters& limit)
{
if(limit.isSoft())
pad = 0.0f;
if(ordinate + pad > limitValue)
addLimit(angular(axis, limitValue - ordinate, PxConstraintSolveHint::eNONE), limit);
}
PX_FORCE_INLINE void angularLimit(const PxVec3& axis, PxReal error, const PxJointLimitParameters& limit)
{
addLimit(angular(axis, error, PxConstraintSolveHint::eNONE), limit);
}
PX_FORCE_INLINE void anglePair(PxReal angle, PxReal lower, PxReal upper, PxReal pad, const PxVec3& axis, const PxJointLimitParameters& limit)
{
PX_ASSERT(lower<upper);
if(limit.isSoft())
pad = 0;
if(angle < lower+pad)
angularLimit(-axis, -(lower - angle), limit);
if(angle > upper-pad)
angularLimit(axis, (upper - angle), limit);
}
// driven linear & angular
PX_FORCE_INLINE void linear(const PxVec3& axis, PxReal velTarget, PxReal error, const PxD6JointDrive& drive)
{
addDrive(linear(axis, error, PxConstraintSolveHint::eNONE), velTarget, drive);
}
PX_FORCE_INLINE void angular(const PxVec3& axis, PxReal velTarget, PxReal error, const PxD6JointDrive& drive, PxConstraintSolveHint::Enum hint = PxConstraintSolveHint::eNONE)
{
addDrive(angular(axis, error, hint), velTarget, drive);
}
PX_FORCE_INLINE PxU32 getCount() const { return PxU32(mCurrent - mConstraints); }
void prepareLockedAxes(const PxQuat& qA, const PxQuat& qB, const PxVec3& cB2cAp, PxU32 lin, PxU32 ang, PxVec3& raOut, PxVec3& rbOut)
{
Px1DConstraint* current = mCurrent;
PxVec3 errorVector(0.f);
PxVec3 ra = mRa;
PxVec3 rb = mRb;
if(lin)
{
const PxMat33 axes(qA);
if(lin&1) errorVector -= axes.column0 * cB2cAp.x;
if(lin&2) errorVector -= axes.column1 * cB2cAp.y;
if(lin&4) errorVector -= axes.column2 * cB2cAp.z;
ra += errorVector;
if(lin&1) _linear(axes.column0, ra, rb, -cB2cAp.x, PxConstraintSolveHint::eEQUALITY, current++);
if(lin&2) _linear(axes.column1, ra, rb, -cB2cAp.y, PxConstraintSolveHint::eEQUALITY, current++);
if(lin&4) _linear(axes.column2, ra, rb, -cB2cAp.z, PxConstraintSolveHint::eEQUALITY, current++);
}
if (ang)
{
const PxQuat qB2qA = qA.getConjugate() * qB;
PxVec3 row[3];
computeJacobianAxes(row, qA, qB);
if (ang & 1) _angular(row[0], -qB2qA.x, PxConstraintSolveHint::eEQUALITY, current++);
if (ang & 2) _angular(row[1], -qB2qA.y, PxConstraintSolveHint::eEQUALITY, current++);
if (ang & 4) _angular(row[2], -qB2qA.z, PxConstraintSolveHint::eEQUALITY, current++);
}
raOut = ra;
rbOut = rb;
for(Px1DConstraint* front = mCurrent; front < current; front++)
front->flags |= Px1DConstraintFlag::eOUTPUT_FORCE;
mCurrent = current;
}
PX_FORCE_INLINE Px1DConstraint* getConstraintRow()
{
return mCurrent++;
}
private:
PX_FORCE_INLINE Px1DConstraint* linear(const PxVec3& axis, PxReal posErr, PxConstraintSolveHint::Enum hint)
{
return _linear(axis, mRa, mRb, posErr, hint, mCurrent++);
}
PX_FORCE_INLINE Px1DConstraint* angular(const PxVec3& axis, PxReal posErr, PxConstraintSolveHint::Enum hint)
{
return _angular(axis, posErr, hint, mCurrent++);
}
void addLimit(Px1DConstraint* c, const PxJointLimitParameters& limit)
{
PxU16 flags = PxU16(c->flags | Px1DConstraintFlag::eOUTPUT_FORCE);
if(limit.isSoft())
{
flags |= Px1DConstraintFlag::eSPRING;
c->mods.spring.stiffness = limit.stiffness;
c->mods.spring.damping = limit.damping;
}
else
{
c->solveHint = PxConstraintSolveHint::eINEQUALITY;
c->mods.bounce.restitution = limit.restitution;
c->mods.bounce.velocityThreshold = limit.bounceThreshold;
if(c->geometricError>0.0f)
flags |= Px1DConstraintFlag::eKEEPBIAS;
if(limit.restitution>0.0f)
flags |= Px1DConstraintFlag::eRESTITUTION;
}
c->flags = flags;
c->minImpulse = 0.0f;
}
void addDrive(Px1DConstraint* c, PxReal velTarget, const PxD6JointDrive& drive)
{
c->velocityTarget = velTarget;
PxU16 flags = PxU16(c->flags | Px1DConstraintFlag::eSPRING | Px1DConstraintFlag::eHAS_DRIVE_LIMIT);
if(drive.flags & PxD6JointDriveFlag::eACCELERATION)
flags |= Px1DConstraintFlag::eACCELERATION_SPRING;
c->flags = flags;
c->mods.spring.stiffness = drive.stiffness;
c->mods.spring.damping = drive.damping;
c->minImpulse = -drive.forceLimit;
c->maxImpulse = drive.forceLimit;
PX_ASSERT(c->linear0.isFinite());
PX_ASSERT(c->angular0.isFinite());
}
};
}
} // namespace
}
#endif

View File

@ -0,0 +1,249 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "ExtContactJoint.h"
#include "PxPhysics.h"
using namespace physx;
using namespace Ext;
PxContactJoint* physx::PxContactJointCreate(PxPhysics& physics, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1)
{
PX_CHECK_AND_RETURN_NULL(localFrame0.isSane(), "PxContactJointCreate: local frame 0 is not a valid transform");
PX_CHECK_AND_RETURN_NULL(localFrame1.isSane(), "PxContactJointCreate: local frame 1 is not a valid transform");
PX_CHECK_AND_RETURN_NULL(actor0 != actor1, "PxContactJointCreate: actors must be different");
PX_CHECK_AND_RETURN_NULL((actor0 && actor0->is<PxRigidBody>()) || (actor1 && actor1->is<PxRigidBody>()), "PxContactJointCreate: at least one actor must be dynamic");
ContactJoint* j;
PX_NEW_SERIALIZED(j, ContactJoint)(physics.getTolerancesScale(), actor0, localFrame0, actor1, localFrame1);
if (j->attach(physics, actor0, actor1))
return j;
PX_DELETE(j);
return NULL;
}
PxVec3 ContactJoint::getContact() const
{
return data().contact;
}
void ContactJoint::setContact(const PxVec3& contact)
{
PX_CHECK_AND_RETURN(contact.isFinite(), "PxContactJoint::setContact: invalid parameter");
data().contact = contact;
markDirty();
}
PxVec3 ContactJoint::getContactNormal() const
{
return data().normal;
}
void ContactJoint::setContactNormal(const PxVec3& normal)
{
PX_CHECK_AND_RETURN(normal.isFinite(), "PxContactJoint::setContactNormal: invalid parameter");
data().normal = normal;
markDirty();
}
PxReal ContactJoint::getPenetration() const
{
return data().penetration;
}
void ContactJoint::setPenetration(PxReal penetration)
{
PX_CHECK_AND_RETURN(PxIsFinite(penetration), "ContactJoint::setPenetration: invalid parameter");
data().penetration = penetration;
markDirty();
}
PxReal ContactJoint::getResititution() const
{
return data().restitution;
}
void ContactJoint::setResititution(const PxReal restitution)
{
PX_CHECK_AND_RETURN(PxIsFinite(restitution) && restitution >= 0.f && restitution <= 1.f, "ContactJoint::setResititution: invalid parameter");
data().restitution = restitution;
markDirty();
}
PxReal ContactJoint::getBounceThreshold() const
{
return data().bounceThreshold;
}
void ContactJoint::setBounceThreshold(const PxReal bounceThreshold)
{
PX_CHECK_AND_RETURN(PxIsFinite(bounceThreshold) && bounceThreshold > 0.f, "ContactJoint::setBounceThreshold: invalid parameter");
data().bounceThreshold = bounceThreshold;
markDirty();
}
bool ContactJoint::attach(PxPhysics &physics, PxRigidActor* actor0, PxRigidActor* actor1)
{
mPxConstraint = physics.createConstraint(actor0, actor1, *this, sShaders, sizeof(ContactJointData));
return mPxConstraint != NULL;
}
void ContactJoint::exportExtraData(PxSerializationContext& stream)
{
if (mData)
{
stream.alignData(PX_SERIAL_ALIGN);
stream.writeData(mData, sizeof(ContactJointData));
}
stream.writeName(mName);
}
void ContactJoint::importExtraData(PxDeserializationContext& context)
{
if (mData)
mData = context.readExtraData<ContactJointData, PX_SERIAL_ALIGN>();
context.readName(mName);
}
void ContactJoint::resolveReferences(PxDeserializationContext& context)
{
setPxConstraint(resolveConstraintPtr(context, getPxConstraint(), getConnector(), sShaders));
}
void ContactJoint::computeJacobians(PxJacobianRow* jacobian) const
{
const PxVec3 cp = data().contact;
const PxVec3 normal = data().normal;
PxRigidActor* actor0, *actor1;
this->getActors(actor0, actor1);
PxVec3 raXn(0.f), rbXn(0.f);
if (actor0 && actor0->is<PxRigidBody>())
{
PxRigidBody* dyn = actor0->is<PxRigidBody>();
PxTransform cmassPose = dyn->getGlobalPose() * dyn->getCMassLocalPose();
raXn = (cp - cmassPose.p).cross(normal);
}
if (actor1 && actor1->is<PxRigidBody>())
{
PxRigidBody* dyn = actor1->is<PxRigidBody>();
PxTransform cmassPose = dyn->getGlobalPose() * dyn->getCMassLocalPose();
rbXn = (cp - cmassPose.p).cross(normal);
}
jacobian->linear0 = normal;
jacobian->angular0 = raXn;
jacobian->linear1 = -normal;
jacobian->angular1 = -rbXn;
}
PxU32 ContactJoint::getNbJacobianRows() const
{
return 1;
}
ContactJoint* ContactJoint::createObject(PxU8*& address, PxDeserializationContext& context)
{
ContactJoint* obj = new (address) ContactJoint(PxBaseFlag::eIS_RELEASABLE);
address += sizeof(ContactJoint);
obj->importExtraData(context);
obj->resolveReferences(context);
return obj;
}
// global function to share the joint shaders with API capture
const PxConstraintShaderTable* Ext::GetContactJointShaderTable()
{
return &ContactJoint::getConstraintShaderTable();
}
//~PX_SERIALIZATION
static void ContactJointProject(const void* /*constantBlock*/, PxTransform& /*bodyAToWorld*/, PxTransform& /*bodyBToWorld*/, bool /*projectToA*/)
{
// Not required
}
static void ContactJointVisualize(PxConstraintVisualizer& /*viz*/, const void* /*constantBlock*/, const PxTransform& /*body0Transform*/, const PxTransform& /*body1Transform*/, PxU32 /*flags*/)
{
//TODO
}
static PxU32 ContactJointSolverPrep(Px1DConstraint* constraints,
PxVec3& body0WorldOffset,
PxU32 /*maxConstraints*/,
PxConstraintInvMassScale& /*invMassScale*/,
const void* constantBlock,
const PxTransform& bA2w,
const PxTransform& bB2w,
bool,
PxVec3& cA2wOut, PxVec3& cB2wOut)
{
const ContactJointData& data = *reinterpret_cast<const ContactJointData*>(constantBlock);
const PxVec3& contact = data.contact;
const PxVec3& normal = data.normal;
cA2wOut = contact;
cB2wOut = contact;
const PxVec3 ra = contact - bA2w.p;
const PxVec3 rb = contact - bB2w.p;
body0WorldOffset = PxVec3(0.f);
Px1DConstraint& con = constraints[0];
con.linear0 = normal;
con.linear1 = normal;
con.angular0 = ra.cross(normal);
con.angular1 = rb.cross(normal);
con.geometricError = data.penetration;
con.minImpulse = 0.f;
con.maxImpulse = PX_MAX_F32;
con.velocityTarget = 0.f;
con.forInternalUse = 0.f;
con.solveHint = 0;
con.flags = Px1DConstraintFlag::eOUTPUT_FORCE;
con.mods.bounce.restitution = data.restitution;
con.mods.bounce.velocityThreshold = data.bounceThreshold;
return 1;
}
PxConstraintShaderTable Ext::ContactJoint::sShaders = { ContactJointSolverPrep, ContactJointProject, ContactJointVisualize, PxConstraintFlag::Enum(0) };

View File

@ -0,0 +1,123 @@
//
// 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-2021 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 NP_CONTACTJOINTCONSTRAINT_H
#define NP_CONTACTJOINTCONSTRAINT_H
#include "common/PxTolerancesScale.h"
#include "extensions/PxContactJoint.h"
#include "ExtJoint.h"
#include "PsUserAllocated.h"
#include "CmUtils.h"
namespace physx
{
struct PxContactJointGeneratedValues;
namespace Ext
{
struct ContactJointData : public JointData
{
PxVec3 contact;
PxVec3 normal;
PxReal penetration;
PxReal restitution;
PxReal bounceThreshold;
};
typedef Joint<PxContactJoint, PxContactJointGeneratedValues> ContactJointT;
class ContactJoint : public ContactJointT
{
public:
// PX_SERIALIZATION
ContactJoint(PxBaseFlags baseFlags) : ContactJointT(baseFlags) {}
virtual void exportExtraData(PxSerializationContext& context);
void importExtraData(PxDeserializationContext& context);
void resolveReferences(PxDeserializationContext& context);
static ContactJoint* createObject(PxU8*& address, PxDeserializationContext& context);
static void getBinaryMetaData(PxOutputStream& stream);
//~PX_SERIALIZATION
ContactJoint(const PxTolerancesScale& scale, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1) :
ContactJointT(PxJointConcreteType::eCONTACT, PxBaseFlag::eOWNS_MEMORY | PxBaseFlag::eIS_RELEASABLE, actor0, localFrame0, actor1, localFrame1, sizeof(ContactJointData), "ContactJointData")
{
PX_UNUSED(scale);
ContactJointData* data = static_cast<ContactJointData*>(mData);
data->contact = PxVec3(0.f);
data->normal = PxVec3(0.f);
data->penetration = 0.f;
data->restitution = 0.f;
data->bounceThreshold = 0.f;
}
// PxContactJoint
virtual PxVec3 getContact() const;
virtual void setContact(const PxVec3& contact);
virtual PxVec3 getContactNormal() const;
virtual void setContactNormal(const PxVec3& normal);
virtual PxReal getPenetration() const;
virtual void setPenetration(const PxReal penetration);
virtual PxReal getResititution() const;
virtual void setResititution(const PxReal resititution);
virtual PxReal getBounceThreshold() const;
virtual void setBounceThreshold(const PxReal bounceThreshold);
virtual void computeJacobians(PxJacobianRow* jacobian) const;
virtual PxU32 getNbJacobianRows() const;
//~PxContactJoint
bool attach(PxPhysics &physics, PxRigidActor* actor0, PxRigidActor* actor1);
static const PxConstraintShaderTable& getConstraintShaderTable() { return sShaders; }
virtual PxConstraintSolverPrep getPrep()const { return sShaders.solverPrep; }
private:
static PxConstraintShaderTable sShaders;
PX_FORCE_INLINE ContactJointData& data() const
{
return *static_cast<ContactJointData*>(mData);
}
};
}// namespace Ext
namespace Ext
{
// global function to share the joint shaders with API capture
extern "C" const PxConstraintShaderTable* GetContactJointShaderTable();
}
}//physx
#endif

View File

@ -0,0 +1,91 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "foundation/PxTransform.h"
#include "geometry/PxConvexMeshGeometry.h"
#include "geometry/PxConvexMesh.h"
#include "extensions/PxConvexMeshExt.h"
using namespace physx;
static const PxReal gEpsilon = .01f;
PxU32 physx::PxFindFaceIndex(const PxConvexMeshGeometry& convexGeom, const PxTransform& pose,
const PxVec3& impactPos, const PxVec3& unitDir)
{
PX_ASSERT(unitDir.isFinite());
PX_ASSERT(unitDir.isNormalized());
PX_ASSERT(impactPos.isFinite());
PX_ASSERT(pose.isFinite());
const PxVec3 impact = impactPos - unitDir * gEpsilon;
const PxVec3 localPoint = pose.transformInv(impact);
const PxVec3 localDir = pose.rotateInv(unitDir);
// Create shape to vertex scale transformation matrix
const PxMeshScale& meshScale = convexGeom.scale;
const PxMat33 rot(meshScale.rotation);
PxMat33 shape2VertexSkew = rot.getTranspose();
const PxMat33 diagonal = PxMat33::createDiagonal(PxVec3(1.0f / meshScale.scale.x, 1.0f / meshScale.scale.y, 1.0f / meshScale.scale.z));
shape2VertexSkew = shape2VertexSkew * diagonal;
shape2VertexSkew = shape2VertexSkew * rot;
const PxU32 nbPolys = convexGeom.convexMesh->getNbPolygons();
PxU32 minIndex = 0;
PxReal minD = PX_MAX_REAL;
for (PxU32 j = 0; j < nbPolys; j++)
{
PxHullPolygon hullPolygon;
convexGeom.convexMesh->getPolygonData(j, hullPolygon);
// transform hull plane into shape space
PxPlane plane;
const PxVec3 tmp = shape2VertexSkew.transformTranspose(PxVec3(hullPolygon.mPlane[0],hullPolygon.mPlane[1],hullPolygon.mPlane[2]));
const PxReal denom = 1.0f / tmp.magnitude();
plane.n = tmp * denom;
plane.d = hullPolygon.mPlane[3] * denom;
PxReal d = plane.distance(localPoint);
if (d < 0.0f)
continue;
const PxReal tweak = plane.n.dot(localDir) * gEpsilon;
d += tweak;
if (d < minD)
{
minIndex = j;
minD = d;
}
}
return minIndex;
}

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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "task/PxTask.h"
#include "ExtCpuWorkerThread.h"
#include "ExtDefaultCpuDispatcher.h"
#include "ExtTaskQueueHelper.h"
#include "PsFPU.h"
using namespace physx;
Ext::CpuWorkerThread::CpuWorkerThread()
: mQueueEntryPool(EXT_TASK_QUEUE_ENTRY_POOL_SIZE),
mThreadId(0)
{
}
Ext::CpuWorkerThread::~CpuWorkerThread()
{
}
void Ext::CpuWorkerThread::initialize(DefaultCpuDispatcher* ownerDispatcher)
{
mOwner = ownerDispatcher;
}
bool Ext::CpuWorkerThread::tryAcceptJobToLocalQueue(PxBaseTask& task, Ps::Thread::Id taskSubmitionThread)
{
if(taskSubmitionThread == mThreadId)
{
SharedQueueEntry* entry = mQueueEntryPool.getEntry(&task);
if (entry)
{
mLocalJobList.push(*entry);
return true;
}
else
return false;
}
return false;
}
PxBaseTask* Ext::CpuWorkerThread::giveUpJob()
{
return TaskQueueHelper::fetchTask(mLocalJobList, mQueueEntryPool);
}
void Ext::CpuWorkerThread::execute()
{
mThreadId = getId();
while (!quitIsSignalled())
{
mOwner->resetWakeSignal();
PxBaseTask* task = TaskQueueHelper::fetchTask(mLocalJobList, mQueueEntryPool);
if(!task)
task = mOwner->fetchNextTask();
if (task)
{
mOwner->runTask(*task);
task->release();
}
else
{
mOwner->waitForWork();
}
}
quit();
}

View File

@ -0,0 +1,79 @@
//
// 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-2021 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_NP_CPU_WORKER_THREAD_H
#define PX_PHYSICS_EXTENSIONS_NP_CPU_WORKER_THREAD_H
#include "CmPhysXCommon.h"
#include "PsThread.h"
#include "ExtDefaultCpuDispatcher.h"
#include "ExtSharedQueueEntryPool.h"
namespace physx
{
namespace Ext
{
class DefaultCpuDispatcher;
#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 // Because of the SList member I assume
class CpuWorkerThread : public Ps::Thread
{
public:
CpuWorkerThread();
~CpuWorkerThread();
void initialize(DefaultCpuDispatcher* ownerDispatcher);
void execute();
bool tryAcceptJobToLocalQueue(PxBaseTask& task, Ps::Thread::Id taskSubmitionThread);
PxBaseTask* giveUpJob();
Ps::Thread::Id getWorkerThreadId() const { return mThreadId; }
protected:
SharedQueueEntryPool<> mQueueEntryPool;
DefaultCpuDispatcher* mOwner;
Ps::SList mLocalJobList;
Ps::Thread::Id mThreadId;
};
#if PX_VC
#pragma warning(pop)
#endif
} // namespace Ext
}
#endif

File diff suppressed because it is too large Load Diff

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-2021 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 NP_D6JOINTCONSTRAINT_H
#define NP_D6JOINTCONSTRAINT_H
#include "extensions/PxD6Joint.h"
#include "ExtJoint.h"
#include "PsMathUtils.h"
namespace physx
{
struct PxD6JointGeneratedValues;
namespace Ext
{
struct D6JointData : public JointData
{
//= 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.
//==================================================================================================
PxD6Motion::Enum motion[6];
PxJointLinearLimit distanceLimit;
PxJointLinearLimitPair linearLimitX;
PxJointLinearLimitPair linearLimitY;
PxJointLinearLimitPair linearLimitZ;
PxJointAngularLimitPair twistLimit;
PxJointLimitCone swingLimit;
PxJointLimitPyramid pyramidSwingLimit;
PxD6JointDrive drive[PxD6Drive::eCOUNT];
PxTransform drivePosition;
PxVec3 driveLinearVelocity;
PxVec3 driveAngularVelocity;
// derived quantities
PxU32 locked; // bitmap of locked DOFs
PxU32 limited; // bitmap of limited DOFs
PxU32 driving; // bitmap of active drives (implies driven DOFs not locked)
PxReal distanceMinDist; // distance limit minimum distance to get a good direction
// projection quantities
PxReal projectionLinearTolerance;
PxReal projectionAngularTolerance;
// PT: the PxD6Motion values are now shared for both kind of linear limits, so we need
// an extra bool to know which one(s) should be actually used.
bool mUseDistanceLimit;
bool mUseNewLinearLimits;
// PT: the swing limits can now be a cone or a pyramid, so we need
// an extra bool to know which one(s) should be actually used.
bool mUseConeLimit;
bool mUsePyramidLimits;
// forestall compiler complaints about not being able to generate a constructor
private:
D6JointData(const PxJointLinearLimit& distance,
const PxJointLinearLimitPair& linearX,
const PxJointLinearLimitPair& linearY,
const PxJointLinearLimitPair& linearZ,
const PxJointAngularLimitPair& twist,
const PxJointLimitCone& swing,
const PxJointLimitPyramid& pyramid) :
distanceLimit (distance),
linearLimitX (linearX),
linearLimitY (linearY),
linearLimitZ (linearZ),
twistLimit (twist),
swingLimit (swing),
pyramidSwingLimit (pyramid),
mUseDistanceLimit (false),
mUseNewLinearLimits (false),
mUseConeLimit (false),
mUsePyramidLimits (false)
{}
};
typedef Joint<PxD6Joint, PxD6JointGeneratedValues> D6JointT;
class D6Joint : public Joint<PxD6Joint, PxD6JointGeneratedValues>
{
public:
// PX_SERIALIZATION
D6Joint(PxBaseFlags baseFlags) : D6JointT(baseFlags) {}
virtual void exportExtraData(PxSerializationContext& context);
void importExtraData(PxDeserializationContext& context);
void resolveReferences(PxDeserializationContext& context);
static D6Joint* createObject(PxU8*& address, PxDeserializationContext& context);
static void getBinaryMetaData(PxOutputStream& stream);
//~PX_SERIALIZATION
D6Joint(const PxTolerancesScale& scale, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1);
// PxD6Joint
virtual void setMotion(PxD6Axis::Enum index, PxD6Motion::Enum t);
virtual PxD6Motion::Enum getMotion(PxD6Axis::Enum index) const;
virtual PxReal getTwistAngle() const;
virtual PxReal getSwingYAngle() const;
virtual PxReal getSwingZAngle() const;
virtual void setDistanceLimit(const PxJointLinearLimit& l);
virtual PxJointLinearLimit getDistanceLimit() const;
virtual void setLinearLimit(PxD6Axis::Enum axis, const PxJointLinearLimitPair& limit);
virtual PxJointLinearLimitPair getLinearLimit(PxD6Axis::Enum axis) const;
virtual void setTwistLimit(const PxJointAngularLimitPair& l);
virtual PxJointAngularLimitPair getTwistLimit() const;
virtual void setSwingLimit(const PxJointLimitCone& l);
virtual PxJointLimitCone getSwingLimit() const;
virtual void setPyramidSwingLimit(const PxJointLimitPyramid& limit);
virtual PxJointLimitPyramid getPyramidSwingLimit() const;
virtual void setDrive(PxD6Drive::Enum index, const PxD6JointDrive& d);
virtual PxD6JointDrive getDrive(PxD6Drive::Enum index) const;
virtual void setDrivePosition(const PxTransform& pose, bool autowake = true);
virtual PxTransform getDrivePosition() const;
virtual void setDriveVelocity(const PxVec3& linear, const PxVec3& angular, bool autowake = true);
virtual void getDriveVelocity(PxVec3& linear, PxVec3& angular) const;
virtual void setProjectionLinearTolerance(PxReal tolerance);
virtual PxReal getProjectionLinearTolerance() const;
virtual void setProjectionAngularTolerance(PxReal tolerance);
virtual PxReal getProjectionAngularTolerance() const;
//~PxD6Joint
void visualize(PxRenderBuffer& out,
const void* constantBlock,
const PxTransform& body0Transform,
const PxTransform& body1Transform,
PxReal frameScale,
PxReal limitScale,
PxU32 flags) const;
bool attach(PxPhysics &physics, PxRigidActor* actor0, PxRigidActor* actor1);
static const PxConstraintShaderTable& getConstraintShaderTable() { return sShaders; }
virtual PxConstraintSolverPrep getPrep() const { return sShaders.solverPrep; }
private:
static PxConstraintShaderTable sShaders;
PX_FORCE_INLINE D6JointData& data() const
{
return *static_cast<D6JointData*>(mData);
}
bool active(const PxD6Drive::Enum index) const
{
PxD6JointDrive& d = data().drive[index];
return d.stiffness!=0 || d.damping != 0;
}
void* prepareData();
bool mRecomputeMotion;
bool mPadding[3]; // PT: padding from prev bool
};
} // namespace Ext
namespace Ext
{
// global function to share the joint shaders with API capture
extern "C" const PxConstraintShaderTable* GetD6JointShaderTable();
}
}
#endif

View File

@ -0,0 +1,289 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "foundation/PxMathUtils.h"
#include "extensions/PxD6JointCreate.h"
#include "extensions/PxD6Joint.h"
#include "extensions/PxFixedJoint.h"
#include "extensions/PxRevoluteJoint.h"
#include "extensions/PxSphericalJoint.h"
#include "extensions/PxPrismaticJoint.h"
#include "extensions/PxDistanceJoint.h"
#include "PxPhysics.h"
using namespace physx;
static const PxVec3 gX(1.0f, 0.0f, 0.0f);
static void setRotY(PxMat33& m, PxReal angle)
{
m = PxMat33(PxIdentity);
const PxReal cos = cosf(angle);
const PxReal sin = sinf(angle);
m[0][0] = m[2][2] = cos;
m[0][2] = -sin;
m[2][0] = sin;
}
static void setRotZ(PxMat33& m, PxReal angle)
{
m = PxMat33(PxIdentity);
const PxReal cos = cosf(angle);
const PxReal sin = sinf(angle);
m[0][0] = m[1][1] = cos;
m[0][1] = sin;
m[1][0] = -sin;
}
static PxQuat getRotYQuat(float angle)
{
PxMat33 m;
setRotY(m, angle);
return PxQuat(m);
}
static PxQuat getRotZQuat(float angle)
{
PxMat33 m;
setRotZ(m, angle);
return PxQuat(m);
}
PxJoint* physx::PxD6JointCreate_Fixed(PxPhysics& physics, PxRigidActor* actor0, const PxVec3& localPos0, PxRigidActor* actor1, const PxVec3& localPos1, bool useD6)
{
const PxTransform jointFrame0(localPos0);
const PxTransform jointFrame1(localPos1);
if(useD6)
// PT: by default all D6 axes are locked, i.e. it is a fixed joint.
return PxD6JointCreate(physics, actor0, jointFrame0, actor1, jointFrame1);
else
return PxFixedJointCreate(physics, actor0, jointFrame0, actor1, jointFrame1);
}
PxJoint* physx::PxD6JointCreate_Distance(PxPhysics& physics, PxRigidActor* actor0, const PxVec3& localPos0, PxRigidActor* actor1, const PxVec3& localPos1, float maxDist, bool useD6)
{
const PxTransform localFrame0(localPos0);
const PxTransform localFrame1(localPos1);
if(useD6)
{
PxD6Joint* j = PxD6JointCreate(physics, actor0, localFrame0, actor1, localFrame1);
j->setMotion(PxD6Axis::eTWIST, PxD6Motion::eFREE);
j->setMotion(PxD6Axis::eSWING1, PxD6Motion::eFREE);
j->setMotion(PxD6Axis::eSWING2, PxD6Motion::eFREE);
j->setMotion(PxD6Axis::eX, PxD6Motion::eLIMITED);
j->setMotion(PxD6Axis::eY, PxD6Motion::eLIMITED);
j->setMotion(PxD6Axis::eZ, PxD6Motion::eLIMITED);
j->setDistanceLimit(PxJointLinearLimit(PxTolerancesScale(), maxDist));
return j;
}
else
{
PxDistanceJoint* j = PxDistanceJointCreate(physics, actor0, localFrame0, actor1, localFrame1);
j->setDistanceJointFlag(PxDistanceJointFlag::eMAX_DISTANCE_ENABLED, true);
j->setMaxDistance(maxDist);
return j;
}
}
PxJoint* physx::PxD6JointCreate_Prismatic(PxPhysics& physics, PxRigidActor* actor0, const PxVec3& localPos0, PxRigidActor* actor1, const PxVec3& localPos1, const PxVec3& axis, float minLimit, float maxLimit, bool useD6)
{
const PxQuat q = PxShortestRotation(gX, axis);
const PxTransform localFrame0(localPos0, q);
const PxTransform localFrame1(localPos1, q);
const PxJointLinearLimitPair limit(PxTolerancesScale(), minLimit, maxLimit);
if(useD6)
{
PxD6Joint* j = PxD6JointCreate(physics, actor0, localFrame0, actor1, localFrame1);
j->setMotion(PxD6Axis::eX, PxD6Motion::eFREE);
if(minLimit==maxLimit)
j->setMotion(PxD6Axis::eX, PxD6Motion::eLOCKED);
else if(minLimit>maxLimit)
j->setMotion(PxD6Axis::eX, PxD6Motion::eFREE);
else// if(minLimit<maxLimit)
{
j->setMotion(PxD6Axis::eX, PxD6Motion::eLIMITED);
j->setLinearLimit(PxD6Axis::eX, limit);
}
return j;
}
else
{
PxPrismaticJoint* j = PxPrismaticJointCreate(physics, actor0, localFrame0, actor1, localFrame1);
if(minLimit<maxLimit)
{
j->setPrismaticJointFlag(PxPrismaticJointFlag::eLIMIT_ENABLED, true);
j->setLimit(limit);
}
return j;
}
}
PxJoint* physx::PxD6JointCreate_Revolute(PxPhysics& physics, PxRigidActor* actor0, const PxVec3& localPos0, PxRigidActor* actor1, const PxVec3& localPos1, const PxVec3& axis, float minLimit, float maxLimit, bool useD6)
{
const PxQuat q = PxShortestRotation(gX, axis);
const PxTransform localFrame0(localPos0, q);
const PxTransform localFrame1(localPos1, q);
const PxJointAngularLimitPair limit(minLimit, maxLimit);
if(useD6)
{
PxD6Joint* j = PxD6JointCreate(physics, actor0, localFrame0, actor1, localFrame1);
if(minLimit==maxLimit)
j->setMotion(PxD6Axis::eTWIST, PxD6Motion::eLOCKED);
else if(minLimit>maxLimit)
j->setMotion(PxD6Axis::eTWIST, PxD6Motion::eFREE);
else// if(minLimit<maxLimit)
{
j->setMotion(PxD6Axis::eTWIST, PxD6Motion::eLIMITED);
j->setTwistLimit(limit);
}
return j;
}
else
{
PxRevoluteJoint* j = PxRevoluteJointCreate(physics, actor0, localFrame0, actor1, localFrame1);
if(minLimit<maxLimit)
{
j->setRevoluteJointFlag(PxRevoluteJointFlag::eLIMIT_ENABLED, true);
j->setLimit(limit);
}
return j;
}
}
PxJoint* physx::PxD6JointCreate_Spherical(PxPhysics& physics, PxRigidActor* actor0, const PxVec3& localPos0, PxRigidActor* actor1, const PxVec3& localPos1, const PxVec3& axis, float limit1, float limit2, bool useD6)
{
const PxQuat q = PxShortestRotation(gX, axis);
const PxTransform localFrame0(localPos0, q);
const PxTransform localFrame1(localPos1, q);
const PxJointLimitCone limit(limit1, limit2);
if(useD6)
{
PxD6Joint* j = PxD6JointCreate(physics, actor0, localFrame0, actor1, localFrame1);
j->setMotion(PxD6Axis::eTWIST, PxD6Motion::eFREE);
if(limit1>0.0f && limit2>0.0f)
{
j->setMotion(PxD6Axis::eSWING1, PxD6Motion::eLIMITED);
j->setMotion(PxD6Axis::eSWING2, PxD6Motion::eLIMITED);
j->setSwingLimit(limit);
}
else
{
j->setMotion(PxD6Axis::eSWING1, PxD6Motion::eFREE);
j->setMotion(PxD6Axis::eSWING2, PxD6Motion::eFREE);
}
return j;
}
else
{
PxSphericalJoint* j = PxSphericalJointCreate(physics, actor0, localFrame0, actor1, localFrame1);
if(limit1>0.0f && limit2>0.0f)
{
j->setSphericalJointFlag(PxSphericalJointFlag::eLIMIT_ENABLED, true);
j->setLimitCone(limit);
}
return j;
}
}
PxJoint* physx::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)
{
const float DesiredMinSwingY = minLimit1;
const float DesiredMaxSwingY = maxLimit1;
const float DesiredMinSwingZ = minLimit2;
const float DesiredMaxSwingZ = maxLimit2;
const float APIMaxY = (DesiredMaxSwingY - DesiredMinSwingY)*0.5f;
const float APIMaxZ = (DesiredMaxSwingZ - DesiredMinSwingZ)*0.5f;
const float APIRotY = (DesiredMaxSwingY + DesiredMinSwingY)*0.5f;
const float APIRotZ = (DesiredMaxSwingZ + DesiredMinSwingZ)*0.5f;
apiroty = APIRotY;
apirotz = APIRotZ;
const PxQuat RotY = getRotYQuat(APIRotY);
const PxQuat RotZ = getRotZQuat(APIRotZ);
const PxQuat Rot = RotY * RotZ;
const PxTransform localFrame0(localPos0, Rot);
const PxTransform localFrame1(localPos1);
const PxJointLimitCone limit(APIMaxY, APIMaxZ);
if(useD6)
{
PxD6Joint* j = PxD6JointCreate(physics, actor0, localFrame0, actor1, localFrame1);
j->setMotion(PxD6Axis::eTWIST, PxD6Motion::eFREE);
j->setMotion(PxD6Axis::eSWING1, PxD6Motion::eLIMITED);
j->setMotion(PxD6Axis::eSWING2, PxD6Motion::eLIMITED);
j->setSwingLimit(limit);
return j;
}
else
{
PxSphericalJoint* j = PxSphericalJointCreate(physics, actor0, localFrame0, actor1, localFrame1);
j->setSphericalJointFlag(PxSphericalJointFlag::eLIMIT_ENABLED, true);
j->setLimitCone(limit);
return j;
}
}
PxJoint* physx::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)
{
const PxQuat q = PxShortestRotation(gX, axis);
const PxTransform localFrame0(localPos0, q);
const PxTransform localFrame1(localPos1, q);
const PxJointLimitPyramid limit(minLimit1, maxLimit1, minLimit2, maxLimit2);
PxD6Joint* j = PxD6JointCreate(physics, actor0, localFrame0, actor1, localFrame1);
j->setMotion(PxD6Axis::eTWIST, PxD6Motion::eFREE);
if(limit.isValid())
{
j->setMotion(PxD6Axis::eSWING1, PxD6Motion::eLIMITED);
j->setMotion(PxD6Axis::eSWING2, PxD6Motion::eLIMITED);
j->setPyramidSwingLimit(limit);
}
else
{
j->setMotion(PxD6Axis::eSWING1, PxD6Motion::eFREE);
j->setMotion(PxD6Axis::eSWING2, PxD6Motion::eFREE);
}
return j;
}

View File

@ -0,0 +1,205 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "ExtDefaultCpuDispatcher.h"
#include "ExtCpuWorkerThread.h"
#include "ExtTaskQueueHelper.h"
#include "PsString.h"
using namespace physx;
PxDefaultCpuDispatcher* physx::PxDefaultCpuDispatcherCreate(PxU32 numThreads, PxU32* affinityMasks)
{
return PX_NEW(Ext::DefaultCpuDispatcher)(numThreads, affinityMasks);
}
#if !PX_PS4 && !PX_XBOXONE && !PX_SWITCH && !PX_XBOX_SERIES_X
void Ext::DefaultCpuDispatcher::getAffinityMasks(PxU32* affinityMasks, PxU32 threadCount)
{
for(PxU32 i=0; i < threadCount; i++)
{
affinityMasks[i] = 0;
}
}
#endif
Ext::DefaultCpuDispatcher::DefaultCpuDispatcher(PxU32 numThreads, PxU32* affinityMasks)
: mQueueEntryPool(EXT_TASK_QUEUE_ENTRY_POOL_SIZE, "QueueEntryPool"), mNumThreads(numThreads), mShuttingDown(false)
#if PX_PROFILE
,mRunProfiled(true)
#else
,mRunProfiled(false)
#endif
{
PxU32* defaultAffinityMasks = NULL;
if(!affinityMasks)
{
defaultAffinityMasks = reinterpret_cast<PxU32*>(PX_ALLOC(numThreads * sizeof(PxU32), "ThreadAffinityMasks"));
getAffinityMasks(defaultAffinityMasks, numThreads);
affinityMasks = defaultAffinityMasks;
}
// initialize threads first, then start
mWorkerThreads = reinterpret_cast<CpuWorkerThread*>(PX_ALLOC(numThreads * sizeof(CpuWorkerThread), "CpuWorkerThread"));
const PxU32 nameLength = 32;
mThreadNames = reinterpret_cast<PxU8*>(PX_ALLOC(nameLength * numThreads, "CpuWorkerThreadName"));
if (mWorkerThreads)
{
for(PxU32 i = 0; i < numThreads; ++i)
{
PX_PLACEMENT_NEW(mWorkerThreads+i, CpuWorkerThread)();
mWorkerThreads[i].initialize(this);
}
for(PxU32 i = 0; i < numThreads; ++i)
{
if (mThreadNames)
{
char* threadName = reinterpret_cast<char*>(mThreadNames + (i*nameLength));
Ps::snprintf(threadName, nameLength, "PxWorker%02d", i);
mWorkerThreads[i].setName(threadName);
}
mWorkerThreads[i].setAffinityMask(affinityMasks[i]);
mWorkerThreads[i].start(Ps::Thread::getDefaultStackSize());
}
if (defaultAffinityMasks)
PX_FREE(defaultAffinityMasks);
}
else
{
mNumThreads = 0;
}
}
Ext::DefaultCpuDispatcher::~DefaultCpuDispatcher()
{
for(PxU32 i = 0; i < mNumThreads; ++i)
mWorkerThreads[i].signalQuit();
mShuttingDown = true;
mWorkReady.set();
for(PxU32 i = 0; i < mNumThreads; ++i)
mWorkerThreads[i].waitForQuit();
for(PxU32 i = 0; i < mNumThreads; ++i)
mWorkerThreads[i].~CpuWorkerThread();
PX_FREE(mWorkerThreads);
if (mThreadNames)
PX_FREE(mThreadNames);
}
void Ext::DefaultCpuDispatcher::submitTask(PxBaseTask& task)
{
if(!mNumThreads)
{
// no worker threads, run directly
runTask(task);
task.release();
return;
}
// TODO: Could use TLS to make this more efficient
const Ps::Thread::Id currentThread = Ps::Thread::getId();
for(PxU32 i = 0; i < mNumThreads; ++i)
{
if(mWorkerThreads[i].tryAcceptJobToLocalQueue(task, currentThread))
return mWorkReady.set();
}
SharedQueueEntry* entry = mQueueEntryPool.getEntry(&task);
if (entry)
{
mJobList.push(*entry);
mWorkReady.set();
}
}
PxBaseTask* Ext::DefaultCpuDispatcher::fetchNextTask()
{
PxBaseTask* task = getJob();
if(!task)
task = stealJob();
return task;
}
void Ext::DefaultCpuDispatcher::release()
{
PX_DELETE(this);
}
PxBaseTask* Ext::DefaultCpuDispatcher::getJob(void)
{
return TaskQueueHelper::fetchTask(mJobList, mQueueEntryPool);
}
PxBaseTask* Ext::DefaultCpuDispatcher::stealJob()
{
PxBaseTask* ret = NULL;
for(PxU32 i = 0; i < mNumThreads; ++i)
{
ret = mWorkerThreads[i].giveUpJob();
if(ret != NULL)
break;
}
return ret;
}
void Ext::DefaultCpuDispatcher::resetWakeSignal()
{
mWorkReady.reset();
// The code below is necessary to avoid deadlocks on shut down.
// A thread usually loops as follows:
// while quit is not signaled
// 1) reset wake signal
// 2) fetch work
// 3) if work -> process
// 4) else -> wait for wake signal
//
// If a thread reaches 1) after the thread pool signaled wake up,
// the wake up sync gets reset and all other threads which have not
// passed 4) already will wait forever.
// The code below makes sure that on shutdown, the wake up signal gets
// sent again after it was reset
//
if (mShuttingDown)
mWorkReady.set();
}

View File

@ -0,0 +1,123 @@
//
// 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-2021 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_NP_DEFAULT_CPU_DISPATCHER_H
#define PX_PHYSICS_EXTENSIONS_NP_DEFAULT_CPU_DISPATCHER_H
#include "common/PxProfileZone.h"
#include "task/PxTask.h"
#include "extensions/PxDefaultCpuDispatcher.h"
#include "CmPhysXCommon.h"
#include "PsUserAllocated.h"
#include "PsSync.h"
#include "PsSList.h"
#include "ExtSharedQueueEntryPool.h"
namespace physx
{
namespace Ext
{
class CpuWorkerThread;
#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 // Because of the SList member I assume
class DefaultCpuDispatcher : public PxDefaultCpuDispatcher, public Ps::UserAllocated
{
friend class TaskQueueHelper;
private:
DefaultCpuDispatcher() : mQueueEntryPool(0) {}
~DefaultCpuDispatcher();
public:
DefaultCpuDispatcher(PxU32 numThreads, PxU32* affinityMasks);
//---------------------------------------------------------------------------------
// PxCpuDispatcher implementation
//---------------------------------------------------------------------------------
virtual void submitTask(PxBaseTask& task);
virtual PxU32 getWorkerCount() const { return mNumThreads; }
//---------------------------------------------------------------------------------
// PxDefaultCpuDispatcher implementation
//---------------------------------------------------------------------------------
virtual void release();
virtual void setRunProfiled(bool runProfiled) { mRunProfiled = runProfiled; }
virtual bool getRunProfiled() const { return mRunProfiled; }
//---------------------------------------------------------------------------------
// DefaultCpuDispatcher
//---------------------------------------------------------------------------------
PxBaseTask* getJob();
PxBaseTask* stealJob();
PxBaseTask* fetchNextTask();
PX_FORCE_INLINE void runTask(PxBaseTask& task)
{
#if PX_SUPPORT_PXTASK_PROFILING
if(mRunProfiled)
{
PX_PROFILE_ZONE(task.getName(), task.getContextId());
task.run();
}
else
#endif
task.run();
}
void waitForWork() { mWorkReady.wait(); }
void resetWakeSignal();
static void getAffinityMasks(PxU32* affinityMasks, PxU32 threadCount);
protected:
CpuWorkerThread* mWorkerThreads;
SharedQueueEntryPool<> mQueueEntryPool;
Ps::SList mJobList;
Ps::Sync mWorkReady;
PxU8* mThreadNames;
PxU32 mNumThreads;
bool mShuttingDown;
bool mRunProfiled;
};
#if PX_VC
#pragma warning(pop)
#endif
} // namespace Ext
}
#endif

View File

@ -0,0 +1,105 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "foundation/PxAssert.h"
#include "extensions/PxDefaultErrorCallback.h"
#include "PsString.h"
#include "PsThread.h"
#include <stdio.h>
using namespace physx;
PxDefaultErrorCallback::PxDefaultErrorCallback()
{
}
PxDefaultErrorCallback::~PxDefaultErrorCallback()
{
}
void PxDefaultErrorCallback::reportError(PxErrorCode::Enum e, const char* message, const char* file, int line)
{
const char* errorCode = NULL;
switch (e)
{
case PxErrorCode::eNO_ERROR:
errorCode = "no error";
break;
case PxErrorCode::eINVALID_PARAMETER:
errorCode = "invalid parameter";
break;
case PxErrorCode::eINVALID_OPERATION:
errorCode = "invalid operation";
break;
case PxErrorCode::eOUT_OF_MEMORY:
errorCode = "out of memory";
break;
case PxErrorCode::eDEBUG_INFO:
errorCode = "info";
break;
case PxErrorCode::eDEBUG_WARNING:
errorCode = "warning";
break;
case PxErrorCode::ePERF_WARNING:
errorCode = "performance warning";
break;
case PxErrorCode::eABORT:
errorCode = "abort";
break;
case PxErrorCode::eINTERNAL_ERROR:
errorCode = "internal error";
break;
case PxErrorCode::eMASK_ALL:
errorCode = "unknown error";
break;
}
PX_ASSERT(errorCode);
if(errorCode)
{
char buffer[1024];
sprintf(buffer, "%s (%d) : %s : %s\n", file, line, errorCode, message);
physx::shdfnd::printString(buffer);
// in debug builds halt execution for abort codes
PX_ASSERT(e != PxErrorCode::eABORT);
// in release builds we also want to halt execution
// and make sure that the error message is flushed
while (e == PxErrorCode::eABORT)
{
physx::shdfnd::printString(buffer);
physx::shdfnd::Thread::sleep(1000);
}
}
}

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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "extensions/PxDefaultSimulationFilterShader.h"
#include "PxRigidActor.h"
#include "PxShape.h"
#include "PsIntrinsics.h"
#include "PsAllocator.h"
#include "PsInlineArray.h"
#include "PsFoundation.h"
#include "CmPhysXCommon.h"
using namespace physx;
namespace
{
#define GROUP_SIZE 32
struct PxCollisionBitMap
{
PX_INLINE PxCollisionBitMap() : enable(true) {}
bool operator()() const { return enable; }
bool& operator= (const bool &v) { enable = v; return enable; }
private:
bool enable;
};
PxCollisionBitMap gCollisionTable[GROUP_SIZE][GROUP_SIZE];
PxFilterOp::Enum gFilterOps[3] = { PxFilterOp::PX_FILTEROP_AND, PxFilterOp::PX_FILTEROP_AND, PxFilterOp::PX_FILTEROP_AND };
PxGroupsMask gFilterConstants[2];
bool gFilterBool = false;
static void gAND(PxGroupsMask& results, const PxGroupsMask& mask0, const PxGroupsMask& mask1)
{
results.bits0 = PxU16(mask0.bits0 & mask1.bits0);
results.bits1 = PxU16(mask0.bits1 & mask1.bits1);
results.bits2 = PxU16(mask0.bits2 & mask1.bits2);
results.bits3 = PxU16(mask0.bits3 & mask1.bits3);
}
static void gOR(PxGroupsMask& results, const PxGroupsMask& mask0, const PxGroupsMask& mask1)
{
results.bits0 = PxU16(mask0.bits0 | mask1.bits0);
results.bits1 = PxU16(mask0.bits1 | mask1.bits1);
results.bits2 = PxU16(mask0.bits2 | mask1.bits2);
results.bits3 = PxU16(mask0.bits3 | mask1.bits3);
}
static void gXOR(PxGroupsMask& results, const PxGroupsMask& mask0, const PxGroupsMask& mask1)
{
results.bits0 = PxU16(mask0.bits0 ^ mask1.bits0);
results.bits1 = PxU16(mask0.bits1 ^ mask1.bits1);
results.bits2 = PxU16(mask0.bits2 ^ mask1.bits2);
results.bits3 = PxU16(mask0.bits3 ^ mask1.bits3);
}
static void gNAND(PxGroupsMask& results, const PxGroupsMask& mask0, const PxGroupsMask& mask1)
{
results.bits0 = PxU16(~(mask0.bits0 & mask1.bits0));
results.bits1 = PxU16(~(mask0.bits1 & mask1.bits1));
results.bits2 = PxU16(~(mask0.bits2 & mask1.bits2));
results.bits3 = PxU16(~(mask0.bits3 & mask1.bits3));
}
static void gNOR(PxGroupsMask& results, const PxGroupsMask& mask0, const PxGroupsMask& mask1)
{
results.bits0 = PxU16(~(mask0.bits0 | mask1.bits0));
results.bits1 = PxU16(~(mask0.bits1 | mask1.bits1));
results.bits2 = PxU16(~(mask0.bits2 | mask1.bits2));
results.bits3 = PxU16(~(mask0.bits3 | mask1.bits3));
}
static void gNXOR(PxGroupsMask& results, const PxGroupsMask& mask0, const PxGroupsMask& mask1)
{
results.bits0 = PxU16(~(mask0.bits0 ^ mask1.bits0));
results.bits1 = PxU16(~(mask0.bits1 ^ mask1.bits1));
results.bits2 = PxU16(~(mask0.bits2 ^ mask1.bits2));
results.bits3 = PxU16(~(mask0.bits3 ^ mask1.bits3));
}
static void gSWAP_AND(PxGroupsMask& results, const PxGroupsMask& mask0, const PxGroupsMask& mask1)
{
results.bits0 = PxU16(mask0.bits0 & mask1.bits2);
results.bits1 = PxU16(mask0.bits1 & mask1.bits3);
results.bits2 = PxU16(mask0.bits2 & mask1.bits0);
results.bits3 = PxU16(mask0.bits3 & mask1.bits1);
}
typedef void (*FilterFunction) (PxGroupsMask& results, const PxGroupsMask& mask0, const PxGroupsMask& mask1);
FilterFunction const gTable[] = { gAND, gOR, gXOR, gNAND, gNOR, gNXOR, gSWAP_AND };
static PxFilterData convert(const PxGroupsMask& mask)
{
PxFilterData fd;
fd.word2 = PxU32(mask.bits0 | (mask.bits1 << 16));
fd.word3 = PxU32(mask.bits2 | (mask.bits3 << 16));
return fd;
}
static PxGroupsMask convert(const PxFilterData& fd)
{
PxGroupsMask mask;
mask.bits0 = PxU16((fd.word2 & 0xffff));
mask.bits1 = PxU16((fd.word2 >> 16));
mask.bits2 = PxU16((fd.word3 & 0xffff));
mask.bits3 = PxU16((fd.word3 >> 16));
return mask;
}
static bool getFilterData(const PxActor& actor, PxFilterData& fd)
{
PxActorType::Enum aType = actor.getType();
switch (aType)
{
case PxActorType::eRIGID_DYNAMIC:
case PxActorType::eRIGID_STATIC:
case PxActorType::eARTICULATION_LINK:
{
const PxRigidActor& rActor = static_cast<const PxRigidActor&>(actor);
PX_CHECK_AND_RETURN_VAL(rActor.getNbShapes() >= 1,"There must be a shape in actor", false);
PxShape* shape = NULL;
rActor.getShapes(&shape, 1);
fd = shape->getSimulationFilterData();
}
break;
case PxActorType::eACTOR_COUNT:
case PxActorType::eACTOR_FORCE_DWORD:
break;
}
return true;
}
PX_FORCE_INLINE static void adjustFilterData(bool groupsMask, const PxFilterData& src, PxFilterData& dst)
{
if (groupsMask)
{
dst.word2 = src.word2;
dst.word3 = src.word3;
}
else
dst.word0 = src.word0;
}
template<bool TGroupsMask>
static void setFilterData(PxActor& actor, const PxFilterData& fd)
{
PxActorType::Enum aType = actor.getType();
switch (aType)
{
case PxActorType::eRIGID_DYNAMIC:
case PxActorType::eRIGID_STATIC:
case PxActorType::eARTICULATION_LINK:
{
const PxRigidActor& rActor = static_cast<const PxRigidActor&>(actor);
PxShape* shape;
for(PxU32 i=0; i < rActor.getNbShapes(); i++)
{
rActor.getShapes(&shape, 1, i);
// retrieve current group mask
PxFilterData resultFd = shape->getSimulationFilterData();
adjustFilterData(TGroupsMask, fd, resultFd);
// set new filter data
shape->setSimulationFilterData(resultFd);
}
}
break;
case PxActorType::eACTOR_COUNT:
case PxActorType::eACTOR_FORCE_DWORD:
break;
}
}
}
PxFilterFlags physx::PxDefaultSimulationFilterShader(
PxFilterObjectAttributes attributes0,
PxFilterData filterData0,
PxFilterObjectAttributes attributes1,
PxFilterData filterData1,
PxPairFlags& pairFlags,
const void* constantBlock,
PxU32 constantBlockSize)
{
PX_UNUSED(constantBlock);
PX_UNUSED(constantBlockSize);
// let triggers through
if(PxFilterObjectIsTrigger(attributes0) || PxFilterObjectIsTrigger(attributes1))
{
pairFlags = PxPairFlag::eTRIGGER_DEFAULT;
return PxFilterFlags();
}
// Collision Group
if (!gCollisionTable[filterData0.word0][filterData1.word0]())
{
return PxFilterFlag::eSUPPRESS;
}
// Filter function
PxGroupsMask g0 = convert(filterData0);
PxGroupsMask g1 = convert(filterData1);
PxGroupsMask g0k0; gTable[gFilterOps[0]](g0k0, g0, gFilterConstants[0]);
PxGroupsMask g1k1; gTable[gFilterOps[1]](g1k1, g1, gFilterConstants[1]);
PxGroupsMask final; gTable[gFilterOps[2]](final, g0k0, g1k1);
bool r = final.bits0 || final.bits1 || final.bits2 || final.bits3;
if (r != gFilterBool)
{
return PxFilterFlag::eSUPPRESS;
}
pairFlags = PxPairFlag::eCONTACT_DEFAULT;
return PxFilterFlags();
}
bool physx::PxGetGroupCollisionFlag(const PxU16 group1, const PxU16 group2)
{
PX_CHECK_AND_RETURN_NULL(group1 < 32 && group2 < 32, "Group must be less than 32");
return gCollisionTable[group1][group2]();
}
void physx::PxSetGroupCollisionFlag(const PxU16 group1, const PxU16 group2, const bool enable)
{
PX_CHECK_AND_RETURN(group1 < 32 && group2 < 32, "Group must be less than 32");
gCollisionTable[group1][group2] = enable;
gCollisionTable[group2][group1] = enable;
}
PxU16 physx::PxGetGroup(const PxActor& actor)
{
PxFilterData fd;
getFilterData(actor, fd);
return PxU16(fd.word0);
}
void physx::PxSetGroup(PxActor& actor, const PxU16 collisionGroup)
{
PX_CHECK_AND_RETURN(collisionGroup < 32,"Collision group must be less than 32");
PxFilterData fd(collisionGroup, 0, 0, 0);
setFilterData<false>(actor, fd);
}
void physx::PxGetFilterOps(PxFilterOp::Enum& op0, PxFilterOp::Enum& op1, PxFilterOp::Enum& op2)
{
op0 = gFilterOps[0];
op1 = gFilterOps[1];
op2 = gFilterOps[2];
}
void physx::PxSetFilterOps(const PxFilterOp::Enum& op0, const PxFilterOp::Enum& op1, const PxFilterOp::Enum& op2)
{
gFilterOps[0] = op0;
gFilterOps[1] = op1;
gFilterOps[2] = op2;
}
bool physx::PxGetFilterBool()
{
return gFilterBool;
}
void physx::PxSetFilterBool(const bool enable)
{
gFilterBool = enable;
}
void physx::PxGetFilterConstants(PxGroupsMask& c0, PxGroupsMask& c1)
{
c0 = gFilterConstants[0];
c1 = gFilterConstants[1];
}
void physx::PxSetFilterConstants(const PxGroupsMask& c0, const PxGroupsMask& c1)
{
gFilterConstants[0] = c0;
gFilterConstants[1] = c1;
}
PxGroupsMask physx::PxGetGroupsMask(const PxActor& actor)
{
PxFilterData fd;
if (getFilterData(actor, fd))
return convert(fd);
else
return PxGroupsMask();
}
void physx::PxSetGroupsMask(PxActor& actor, const PxGroupsMask& mask)
{
PxFilterData fd = convert(mask);
setFilterData<true>(actor, fd);
}

View File

@ -0,0 +1,195 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "foundation/PxPreprocessor.h"
#include "foundation/PxAssert.h"
#include "foundation/PxAllocatorCallback.h"
#include "foundation/PxMemory.h"
#include "extensions/PxDefaultStreams.h"
#include "PsFoundation.h"
#include "SnFile.h"
#include "CmPhysXCommon.h"
#include "PsUtilities.h"
#include "PsBitUtils.h"
#include <errno.h>
using namespace physx;
PxDefaultMemoryOutputStream::PxDefaultMemoryOutputStream(PxAllocatorCallback &allocator)
: mAllocator (allocator)
, mData (NULL)
, mSize (0)
, mCapacity (0)
{
}
PxDefaultMemoryOutputStream::~PxDefaultMemoryOutputStream()
{
if(mData)
mAllocator.deallocate(mData);
}
PxU32 PxDefaultMemoryOutputStream::write(const void* src, PxU32 size)
{
PxU32 expectedSize = mSize + size;
if(expectedSize > mCapacity)
{
mCapacity = PxMax(Ps::nextPowerOfTwo(expectedSize), 4096u);
PxU8* newData = reinterpret_cast<PxU8*>(mAllocator.allocate(mCapacity,"PxDefaultMemoryOutputStream",__FILE__,__LINE__));
PX_ASSERT(newData!=NULL);
PxMemCopy(newData, mData, mSize);
if(mData)
mAllocator.deallocate(mData);
mData = newData;
}
PxMemCopy(mData+mSize, src, size);
mSize += size;
return size;
}
///////////////////////////////////////////////////////////////////////////////
PxDefaultMemoryInputData::PxDefaultMemoryInputData(PxU8* data, PxU32 length) :
mSize (length),
mData (data),
mPos (0)
{
}
PxU32 PxDefaultMemoryInputData::read(void* dest, PxU32 count)
{
PxU32 length = PxMin<PxU32>(count, mSize-mPos);
PxMemCopy(dest, mData+mPos, length);
mPos += length;
return length;
}
PxU32 PxDefaultMemoryInputData::getLength() const
{
return mSize;
}
void PxDefaultMemoryInputData::seek(PxU32 offset)
{
mPos = PxMin<PxU32>(mSize, offset);
}
PxU32 PxDefaultMemoryInputData::tell() const
{
return mPos;
}
PxDefaultFileOutputStream::PxDefaultFileOutputStream(const char* filename)
{
mFile = NULL;
sn::fopen_s(&mFile, filename, "wb");
// PT: when this fails, check that:
// - the path is correct
// - the file does not already exist. If it does, check that it is not write protected.
if(NULL == mFile)
{
Ps::getFoundation().error(PxErrorCode::eINTERNAL_ERROR, __FILE__, __LINE__,
"Unable to open file %s, errno 0x%x\n",filename,errno);
}
PX_ASSERT(mFile);
}
PxDefaultFileOutputStream::~PxDefaultFileOutputStream()
{
if(mFile)
fclose(mFile);
}
PxU32 PxDefaultFileOutputStream::write(const void* src, PxU32 count)
{
return mFile ? PxU32(fwrite(src, 1, count, mFile)) : 0;
}
bool PxDefaultFileOutputStream::isValid()
{
return mFile != NULL;
}
///////////////////////////////////////////////////////////////////////////////
PxDefaultFileInputData::PxDefaultFileInputData(const char* filename)
{
mFile = NULL;
sn::fopen_s(&mFile, filename, "rb");
if(mFile)
{
fseek(mFile, 0, SEEK_END);
mLength = PxU32(ftell(mFile));
fseek(mFile, 0, SEEK_SET);
}
else
{
mLength = 0;
}
}
PxDefaultFileInputData::~PxDefaultFileInputData()
{
if(mFile)
fclose(mFile);
}
PxU32 PxDefaultFileInputData::read(void* dest, PxU32 count)
{
PX_ASSERT(mFile);
const size_t size = fread(dest, 1, count, mFile);
// there should be no assert here since by spec of PxInputStream we can read fewer bytes than expected
return PxU32(size);
}
PxU32 PxDefaultFileInputData::getLength() const
{
return mLength;
}
void PxDefaultFileInputData::seek(PxU32 pos)
{
fseek(mFile, long(pos), SEEK_SET);
}
PxU32 PxDefaultFileInputData::tell() const
{
return PxU32(ftell(mFile));
}
bool PxDefaultFileInputData::isValid() const
{
return mFile != NULL;
}

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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "ExtDistanceJoint.h"
#include "ExtConstraintHelper.h"
#include "PxPhysics.h"
using namespace physx;
using namespace Ext;
PxDistanceJoint* physx::PxDistanceJointCreate(PxPhysics& physics, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1)
{
PX_CHECK_AND_RETURN_NULL(localFrame0.isSane(), "PxDistanceJointCreate: local frame 0 is not a valid transform");
PX_CHECK_AND_RETURN_NULL(localFrame1.isSane(), "PxDistanceJointCreate: local frame 1 is not a valid transform");
PX_CHECK_AND_RETURN_NULL(actor0 != actor1, "PxDistanceJointCreate: actors must be different");
PX_CHECK_AND_RETURN_NULL((actor0 && actor0->is<PxRigidBody>()) || (actor1 && actor1->is<PxRigidBody>()), "PxD6JointCreate: at least one actor must be dynamic");
DistanceJoint* j;
PX_NEW_SERIALIZED(j, DistanceJoint)(physics.getTolerancesScale(), actor0, localFrame0, actor1, localFrame1);
if(j->attach(physics, actor0, actor1))
return j;
PX_DELETE(j);
return NULL;
}
PxReal DistanceJoint::getDistance() const
{
return getRelativeTransform().p.magnitude();
}
void DistanceJoint::setMinDistance(PxReal distance)
{
PX_CHECK_AND_RETURN(PxIsFinite(distance), "PxDistanceJoint::setMinDistance: invalid parameter");
data().minDistance = distance;
markDirty();
}
PxReal DistanceJoint::getMinDistance() const
{
return data().minDistance;
}
void DistanceJoint::setMaxDistance(PxReal distance)
{
PX_CHECK_AND_RETURN(PxIsFinite(distance), "PxDistanceJoint::setMaxDistance: invalid parameter");
data().maxDistance = distance;
markDirty();
}
PxReal DistanceJoint::getMaxDistance() const
{
return data().maxDistance;
}
void DistanceJoint::setTolerance(PxReal tolerance)
{
PX_CHECK_AND_RETURN(PxIsFinite(tolerance), "PxDistanceJoint::setTolerance: invalid parameter");
data().tolerance = tolerance;
markDirty();
}
PxReal DistanceJoint::getTolerance() const
{
return data().tolerance;
}
void DistanceJoint::setStiffness(PxReal stiffness)
{
PX_CHECK_AND_RETURN(PxIsFinite(stiffness), "PxDistanceJoint::setStiffness: invalid parameter");
data().stiffness = stiffness;
markDirty();
}
PxReal DistanceJoint::getStiffness() const
{
return data().stiffness;
}
void DistanceJoint::setDamping(PxReal damping)
{
PX_CHECK_AND_RETURN(PxIsFinite(damping), "PxDistanceJoint::setDamping: invalid parameter");
data().damping = damping;
markDirty();
}
PxReal DistanceJoint::getDamping() const
{
return data().damping;
}
PxDistanceJointFlags DistanceJoint::getDistanceJointFlags(void) const
{
return data().jointFlags;
}
void DistanceJoint::setDistanceJointFlags(PxDistanceJointFlags flags)
{
data().jointFlags = flags;
markDirty();
}
void DistanceJoint::setDistanceJointFlag(PxDistanceJointFlag::Enum flag, bool value)
{
if(value)
data().jointFlags |= flag;
else
data().jointFlags &= ~flag;
markDirty();
}
bool DistanceJoint::attach(PxPhysics &physics, PxRigidActor* actor0, PxRigidActor* actor1)
{
mPxConstraint = physics.createConstraint(actor0, actor1, *this, sShaders, sizeof(DistanceJointData));
return mPxConstraint!=NULL;
}
void DistanceJoint::exportExtraData(PxSerializationContext& stream)
{
if(mData)
{
stream.alignData(PX_SERIAL_ALIGN);
stream.writeData(mData, sizeof(DistanceJointData));
}
stream.writeName(mName);
}
void DistanceJoint::importExtraData(PxDeserializationContext& context)
{
if(mData)
mData = context.readExtraData<DistanceJointData, PX_SERIAL_ALIGN>();
context.readName(mName);
}
void DistanceJoint::resolveReferences(PxDeserializationContext& context)
{
setPxConstraint(resolveConstraintPtr(context, getPxConstraint(), getConnector(), sShaders));
}
DistanceJoint* DistanceJoint::createObject(PxU8*& address, PxDeserializationContext& context)
{
DistanceJoint* obj = new (address) DistanceJoint(PxBaseFlag::eIS_RELEASABLE);
address += sizeof(DistanceJoint);
obj->importExtraData(context);
obj->resolveReferences(context);
return obj;
}
// global function to share the joint shaders with API capture
const PxConstraintShaderTable* Ext::GetDistanceJointShaderTable()
{
return &DistanceJoint::getConstraintShaderTable();
}
//~PX_SERIALIZATION
static void DistanceJointProject(const void* /*constantBlock*/, PxTransform& /*bodyAToWorld*/, PxTransform& /*bodyBToWorld*/, bool /*projectToA*/)
{
// TODO
}
static void DistanceJointVisualize(PxConstraintVisualizer& viz, const void* constantBlock, const PxTransform& body0Transform, const PxTransform& body1Transform, PxU32 flags)
{
const DistanceJointData& data = *reinterpret_cast<const DistanceJointData*>(constantBlock);
PxTransform cA2w, cB2w;
joint::computeJointFrames(cA2w, cB2w, data, body0Transform, body1Transform);
if(flags & PxConstraintVisualizationFlag::eLOCAL_FRAMES)
viz.visualizeJointFrames(cA2w, cB2w);
// PT: we consider the following is part of the joint's "limits" since that's the only available flag we have
if(flags & PxConstraintVisualizationFlag::eLIMITS)
{
const bool enforceMax = (data.jointFlags & PxDistanceJointFlag::eMAX_DISTANCE_ENABLED);
const bool enforceMin = (data.jointFlags & PxDistanceJointFlag::eMIN_DISTANCE_ENABLED);
if(!enforceMin && !enforceMax)
return;
PxVec3 dir = cB2w.p - cA2w.p;
const float currentDist = dir.normalize();
PxU32 color = 0x00ff00;
if(enforceMax && currentDist>data.maxDistance)
color = 0xff0000;
if(enforceMin && currentDist<data.minDistance)
color = 0x0000ff;
viz.visualizeLine(cA2w.p, cB2w.p, color);
}
}
PX_FORCE_INLINE void setupContraint(Px1DConstraint& c, const PxVec3& direction, const PxVec3& angular0, const PxVec3& angular1, const DistanceJointData& data)
{
// constraint is breakable, so we need to output forces
c.flags = Px1DConstraintFlag::eOUTPUT_FORCE;
c.linear0 = direction; c.angular0 = angular0;
c.linear1 = direction; c.angular1 = angular1;
if(data.jointFlags & PxDistanceJointFlag::eSPRING_ENABLED)
{
c.flags |= Px1DConstraintFlag::eSPRING;
c.mods.spring.stiffness= data.stiffness;
c.mods.spring.damping = data.damping;
}
}
static PxU32 DistanceJointSolverPrep(Px1DConstraint* constraints,
PxVec3& body0WorldOffset,
PxU32 /*maxConstraints*/,
PxConstraintInvMassScale& invMassScale,
const void* constantBlock,
const PxTransform& bA2w,
const PxTransform& bB2w,
bool /*useExtendedLimits*/,
PxVec3& cA2wOut, PxVec3& cB2wOut)
{
const DistanceJointData& data = *reinterpret_cast<const DistanceJointData*>(constantBlock);
PxTransform cA2w, cB2w;
joint::ConstraintHelper ch(constraints, invMassScale, cA2w, cB2w, body0WorldOffset, data, bA2w, bB2w);
cA2wOut = cB2w.p;
cB2wOut = cB2w.p;
PxVec3 direction = cA2w.p - cB2w.p;
const PxReal distance = direction.normalize();
const bool enforceMax = (data.jointFlags & PxDistanceJointFlag::eMAX_DISTANCE_ENABLED);
const bool enforceMin = (data.jointFlags & PxDistanceJointFlag::eMIN_DISTANCE_ENABLED);
#define EPS_REAL 1.192092896e-07F
if(distance < EPS_REAL)
direction = PxVec3(1.0f, 0.0f, 0.0f);
Px1DConstraint* c = constraints;
const PxVec3 angular0 = ch.getRa().cross(direction);
const PxVec3 angular1 = ch.getRb().cross(direction);
setupContraint(*c, direction, angular0, angular1, data);
//add tolerance so we don't have contact-style jitter problem.
if(data.minDistance == data.maxDistance && enforceMin && enforceMax)
{
const PxReal error = distance - data.maxDistance;
c->geometricError = error > data.tolerance ? error - data.tolerance :
error < -data.tolerance ? error + data.tolerance : 0.0f;
}
else if(enforceMax && distance > data.maxDistance)
{
c->geometricError = distance - data.maxDistance - data.tolerance;
c->maxImpulse = 0.0f;
}
else if(enforceMin && distance < data.minDistance)
{
c->geometricError = distance - data.minDistance + data.tolerance;
c->minImpulse = 0.0f;
}
else
{
if(enforceMin && enforceMax)
{
// since we dont know the current rigid velocity, we need to insert row for both limits
Px1DConstraint* minConstraint = constraints;
minConstraint->geometricError = distance - data.minDistance;
minConstraint->minImpulse = 0.0f;
minConstraint->maxImpulse = FLT_MAX;
minConstraint->flags |= Px1DConstraintFlag::eKEEPBIAS;
Px1DConstraint* maxConstraint = constraints;
maxConstraint++;
setupContraint(*maxConstraint, direction, angular0, angular1, data);
maxConstraint->geometricError = distance - data.maxDistance;
maxConstraint->minImpulse = -FLT_MAX;
maxConstraint->maxImpulse = 0.0f;
maxConstraint->flags |= Px1DConstraintFlag::eKEEPBIAS;
return 2;
}
else if(enforceMax)
{
c->geometricError = distance - data.maxDistance;
c->minImpulse = -FLT_MAX;
c->maxImpulse = 0.0f;
c->flags |= Px1DConstraintFlag::eKEEPBIAS;
return 0;
}
else if(enforceMin)
{
c->geometricError = distance - data.minDistance;
c->minImpulse = 0.0f;
c->maxImpulse = FLT_MAX;
c->flags |= Px1DConstraintFlag::eKEEPBIAS;
return 0;
}
}
return 1;
}
PxConstraintShaderTable Ext::DistanceJoint::sShaders = { DistanceJointSolverPrep, DistanceJointProject, DistanceJointVisualize, PxConstraintFlag::Enum(0) };

View File

@ -0,0 +1,140 @@
//
// 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-2021 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 NP_DISTANCEJOINTCONSTRAINT_H
#define NP_DISTANCEJOINTCONSTRAINT_H
#include "common/PxTolerancesScale.h"
#include "extensions/PxDistanceJoint.h"
#include "ExtJoint.h"
#include "PsUserAllocated.h"
#include "CmUtils.h"
namespace physx
{
struct PxDistanceJointGeneratedValues;
namespace Ext
{
struct DistanceJointData : public JointData
{
//= 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 minDistance;
PxReal maxDistance;
PxReal tolerance;
PxReal stiffness;
PxReal damping;
PxDistanceJointFlags jointFlags;
};
typedef Joint<PxDistanceJoint, PxDistanceJointGeneratedValues> DistanceJointT;
class DistanceJoint : public DistanceJointT
{
//= 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:
// PX_SERIALIZATION
DistanceJoint(PxBaseFlags baseFlags) : DistanceJointT(baseFlags) {}
virtual void exportExtraData(PxSerializationContext& context);
void importExtraData(PxDeserializationContext& context);
void resolveReferences(PxDeserializationContext& context);
static DistanceJoint* createObject(PxU8*& address, PxDeserializationContext& context);
static void getBinaryMetaData(PxOutputStream& stream);
//~PX_SERIALIZATION
DistanceJoint(const PxTolerancesScale& scale, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1) :
DistanceJointT(PxJointConcreteType::eDISTANCE, PxBaseFlag::eOWNS_MEMORY | PxBaseFlag::eIS_RELEASABLE, actor0, localFrame0, actor1, localFrame1, sizeof(DistanceJointData), "DistanceJointData")
{
DistanceJointData* data = static_cast<DistanceJointData*>(mData);
data->stiffness = 0.0f;
data->damping = 0.0f;
data->minDistance = 0.0f;
data->maxDistance = 0.0f;
data->tolerance = 0.025f * scale.length;
data->jointFlags = PxDistanceJointFlag::eMAX_DISTANCE_ENABLED;
}
// PxDistanceJoint
virtual PxReal getDistance() const;
virtual void setMinDistance(PxReal distance);
virtual PxReal getMinDistance() const;
virtual void setMaxDistance(PxReal distance);
virtual PxReal getMaxDistance() const;
virtual void setTolerance(PxReal tolerance);
virtual PxReal getTolerance() const;
virtual void setStiffness(PxReal spring);
virtual PxReal getStiffness() const;
virtual void setDamping(PxReal damping);
virtual PxReal getDamping() const;
virtual void setDistanceJointFlags(PxDistanceJointFlags flags);
virtual void setDistanceJointFlag(PxDistanceJointFlag::Enum flag, bool value);
virtual PxDistanceJointFlags getDistanceJointFlags() const;
//~PxDistanceJoint
bool attach(PxPhysics &physics, PxRigidActor* actor0, PxRigidActor* actor1);
static const PxConstraintShaderTable& getConstraintShaderTable() { return sShaders; }
virtual PxConstraintSolverPrep getPrep()const {return sShaders.solverPrep;}
private:
static PxConstraintShaderTable sShaders;
PX_FORCE_INLINE DistanceJointData& data() const
{
return *static_cast<DistanceJointData*>(mData);
}
};
} // namespace Ext
namespace Ext
{
// global function to share the joint shaders with API capture
extern "C" const PxConstraintShaderTable* GetDistanceJointShaderTable();
}
}
#endif

View File

@ -0,0 +1,191 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "foundation/PxIO.h"
#include "common/PxMetaData.h"
#include "common/PxSerializer.h"
#include "extensions/PxExtensionsAPI.h"
#include "extensions/PxRepXSerializer.h"
#include "PsFoundation.h"
#include "ExtDistanceJoint.h"
#include "ExtD6Joint.h"
#include "ExtFixedJoint.h"
#include "ExtPrismaticJoint.h"
#include "ExtRevoluteJoint.h"
#include "ExtSphericalJoint.h"
#include "ExtSerialization.h"
#include "SnRepXCoreSerializer.h"
#include "SnJointRepXSerializer.h"
#include "PxExtensionMetaDataObjects.h"
#if PX_SUPPORT_PVD
#include "ExtPvd.h"
#include "PxPvdDataStream.h"
#include "PxPvdClient.h"
#include "PsPvd.h"
#endif
using namespace physx;
using namespace physx::pvdsdk;
#if PX_SUPPORT_PVD
struct JointConnectionHandler : public PvdClient
{
JointConnectionHandler() : mPvd(NULL),mConnected(false){}
PvdDataStream* getDataStream()
{
return NULL;
}
void onPvdConnected()
{
PvdDataStream* stream = PvdDataStream::create(mPvd);
if(stream)
{
mConnected = true;
Ext::Pvd::sendClassDescriptions(*stream);
stream->release();
}
}
bool isConnected() const
{
return mConnected;
}
void onPvdDisconnected()
{
mConnected = false;
}
void flush()
{
}
PsPvd* mPvd;
bool mConnected;
};
static JointConnectionHandler gPvdHandler;
#endif
bool PxInitExtensions(PxPhysics& physics, PxPvd* pvd)
{
PX_ASSERT(static_cast<Ps::Foundation*>(&physics.getFoundation()) == &Ps::Foundation::getInstance());
PX_UNUSED(physics);
PX_UNUSED(pvd);
Ps::Foundation::incRefCount();
#if PX_SUPPORT_PVD
if(pvd)
{
gPvdHandler.mPvd = static_cast<PsPvd*>(pvd);
gPvdHandler.mPvd->addClient(&gPvdHandler);
}
#endif
return true;
}
void PxCloseExtensions(void)
{
Ps::Foundation::decRefCount();
#if PX_SUPPORT_PVD
if(gPvdHandler.mConnected)
{
PX_ASSERT(gPvdHandler.mPvd);
gPvdHandler.mPvd->removeClient(&gPvdHandler);
gPvdHandler.mPvd = NULL;
}
#endif
}
void Ext::RegisterExtensionsSerializers(PxSerializationRegistry& sr)
{
//for repx serialization
sr.registerRepXSerializer(PxConcreteType::eMATERIAL, PX_NEW_REPX_SERIALIZER( PxMaterialRepXSerializer ));
sr.registerRepXSerializer(PxConcreteType::eSHAPE, PX_NEW_REPX_SERIALIZER( PxShapeRepXSerializer ));
sr.registerRepXSerializer(PxConcreteType::eTRIANGLE_MESH_BVH33, PX_NEW_REPX_SERIALIZER( PxBVH33TriangleMeshRepXSerializer ));
sr.registerRepXSerializer(PxConcreteType::eTRIANGLE_MESH_BVH34, PX_NEW_REPX_SERIALIZER( PxBVH34TriangleMeshRepXSerializer ));
sr.registerRepXSerializer(PxConcreteType::eHEIGHTFIELD, PX_NEW_REPX_SERIALIZER( PxHeightFieldRepXSerializer ));
sr.registerRepXSerializer(PxConcreteType::eCONVEX_MESH, PX_NEW_REPX_SERIALIZER( PxConvexMeshRepXSerializer ));
sr.registerRepXSerializer(PxConcreteType::eRIGID_STATIC, PX_NEW_REPX_SERIALIZER( PxRigidStaticRepXSerializer ));
sr.registerRepXSerializer(PxConcreteType::eRIGID_DYNAMIC, PX_NEW_REPX_SERIALIZER( PxRigidDynamicRepXSerializer ));
sr.registerRepXSerializer(PxConcreteType::eARTICULATION, PX_NEW_REPX_SERIALIZER( PxArticulationRepXSerializer ));
sr.registerRepXSerializer(PxConcreteType::eARTICULATION_REDUCED_COORDINATE, PX_NEW_REPX_SERIALIZER( PxArticulationReducedCoordinateRepXSerializer));
sr.registerRepXSerializer(PxConcreteType::eAGGREGATE, PX_NEW_REPX_SERIALIZER( PxAggregateRepXSerializer ));
sr.registerRepXSerializer(PxJointConcreteType::eFIXED, PX_NEW_REPX_SERIALIZER( PxJointRepXSerializer<PxFixedJoint> ));
sr.registerRepXSerializer(PxJointConcreteType::eDISTANCE, PX_NEW_REPX_SERIALIZER( PxJointRepXSerializer<PxDistanceJoint> ));
sr.registerRepXSerializer(PxJointConcreteType::eD6, PX_NEW_REPX_SERIALIZER( PxJointRepXSerializer<PxD6Joint> ));
sr.registerRepXSerializer(PxJointConcreteType::ePRISMATIC, PX_NEW_REPX_SERIALIZER( PxJointRepXSerializer<PxPrismaticJoint> ));
sr.registerRepXSerializer(PxJointConcreteType::eREVOLUTE, PX_NEW_REPX_SERIALIZER( PxJointRepXSerializer<PxRevoluteJoint> ));
sr.registerRepXSerializer(PxJointConcreteType::eSPHERICAL, PX_NEW_REPX_SERIALIZER( PxJointRepXSerializer<PxSphericalJoint> ));
//for binary serialization
sr.registerSerializer(PxJointConcreteType::eFIXED, PX_NEW_SERIALIZER_ADAPTER( FixedJoint ));
sr.registerSerializer(PxJointConcreteType::eDISTANCE, PX_NEW_SERIALIZER_ADAPTER( DistanceJoint ));
sr.registerSerializer(PxJointConcreteType::eD6, PX_NEW_SERIALIZER_ADAPTER( D6Joint) );
sr.registerSerializer(PxJointConcreteType::ePRISMATIC, PX_NEW_SERIALIZER_ADAPTER( PrismaticJoint ));
sr.registerSerializer(PxJointConcreteType::eREVOLUTE, PX_NEW_SERIALIZER_ADAPTER( RevoluteJoint ));
sr.registerSerializer(PxJointConcreteType::eSPHERICAL, PX_NEW_SERIALIZER_ADAPTER( SphericalJoint ));
}
void Ext::UnregisterExtensionsSerializers(PxSerializationRegistry& sr)
{
PX_DELETE_SERIALIZER_ADAPTER(sr.unregisterSerializer(PxJointConcreteType::eFIXED));
PX_DELETE_SERIALIZER_ADAPTER(sr.unregisterSerializer(PxJointConcreteType::eDISTANCE));
PX_DELETE_SERIALIZER_ADAPTER(sr.unregisterSerializer(PxJointConcreteType::eD6 ));
PX_DELETE_SERIALIZER_ADAPTER(sr.unregisterSerializer(PxJointConcreteType::ePRISMATIC));
PX_DELETE_SERIALIZER_ADAPTER(sr.unregisterSerializer(PxJointConcreteType::eREVOLUTE));
PX_DELETE_SERIALIZER_ADAPTER(sr.unregisterSerializer(PxJointConcreteType::eSPHERICAL));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxConcreteType::eMATERIAL));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxConcreteType::eSHAPE));
// PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxConcreteType::eTRIANGLE_MESH));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxConcreteType::eTRIANGLE_MESH_BVH33));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxConcreteType::eTRIANGLE_MESH_BVH34));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxConcreteType::eHEIGHTFIELD));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxConcreteType::eCONVEX_MESH));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxConcreteType::eRIGID_STATIC));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxConcreteType::eRIGID_DYNAMIC));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxConcreteType::eARTICULATION));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxConcreteType::eARTICULATION_REDUCED_COORDINATE));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxConcreteType::eAGGREGATE));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxJointConcreteType::eFIXED));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxJointConcreteType::eDISTANCE));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxJointConcreteType::eD6));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxJointConcreteType::ePRISMATIC));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxJointConcreteType::eREVOLUTE));
PX_DELETE_REPX_SERIALIZER(sr.unregisterRepXSerializer(PxJointConcreteType::eSPHERICAL));
}

View File

@ -0,0 +1,175 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "ExtFixedJoint.h"
#include "ExtConstraintHelper.h"
#include "PxPhysics.h"
using namespace physx;
using namespace Ext;
PxFixedJoint* physx::PxFixedJointCreate(PxPhysics& physics, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1)
{
PX_CHECK_AND_RETURN_NULL(localFrame0.isSane(), "PxFixedJointCreate: local frame 0 is not a valid transform");
PX_CHECK_AND_RETURN_NULL(localFrame1.isSane(), "PxFixedJointCreate: local frame 1 is not a valid transform");
PX_CHECK_AND_RETURN_NULL((actor0 && actor0->is<PxRigidBody>()) || (actor1 && actor1->is<PxRigidBody>()), "PxFixedJointCreate: at least one actor must be dynamic");
PX_CHECK_AND_RETURN_NULL(actor0 != actor1, "PxFixedJointCreate: actors must be different");
FixedJoint* j;
PX_NEW_SERIALIZED(j, FixedJoint)(physics.getTolerancesScale(), actor0, localFrame0, actor1, localFrame1);
if(j->attach(physics, actor0, actor1))
return j;
PX_DELETE(j);
return NULL;
}
PxReal FixedJoint::getProjectionLinearTolerance() const
{
return data().projectionLinearTolerance;
}
void FixedJoint::setProjectionLinearTolerance(PxReal tolerance)
{
PX_CHECK_AND_RETURN(PxIsFinite(tolerance) && tolerance >=0, "PxFixedJoint::setProjectionLinearTolerance: invalid parameter");
data().projectionLinearTolerance = tolerance;
markDirty();
}
PxReal FixedJoint::getProjectionAngularTolerance() const
{
return data().projectionAngularTolerance;
}
void FixedJoint::setProjectionAngularTolerance(PxReal tolerance)
{
PX_CHECK_AND_RETURN(PxIsFinite(tolerance) && tolerance >=0 && tolerance <= PxPi, "PxFixedJoint::setProjectionAngularTolerance: invalid parameter");
data().projectionAngularTolerance = tolerance; markDirty();
}
bool FixedJoint::attach(PxPhysics &physics, PxRigidActor* actor0, PxRigidActor* actor1)
{
mPxConstraint = physics.createConstraint(actor0, actor1, *this, sShaders, sizeof(FixedJointData));
return mPxConstraint!=NULL;
}
void FixedJoint::exportExtraData(PxSerializationContext& stream) const
{
if(mData)
{
stream.alignData(PX_SERIAL_ALIGN);
stream.writeData(mData, sizeof(FixedJointData));
}
stream.writeName(mName);
}
void FixedJoint::importExtraData(PxDeserializationContext& context)
{
if(mData)
mData = context.readExtraData<FixedJointData, PX_SERIAL_ALIGN>();
context.readName(mName);
}
void FixedJoint::resolveReferences(PxDeserializationContext& context)
{
setPxConstraint(resolveConstraintPtr(context, getPxConstraint(), getConnector(), sShaders));
}
FixedJoint* FixedJoint::createObject(PxU8*& address, PxDeserializationContext& context)
{
FixedJoint* obj = new (address) FixedJoint(PxBaseFlag::eIS_RELEASABLE);
address += sizeof(FixedJoint);
obj->importExtraData(context);
obj->resolveReferences(context);
return obj;
}
// global function to share the joint shaders with API capture
const PxConstraintShaderTable* Ext::GetFixedJointShaderTable()
{
return &FixedJoint::getConstraintShaderTable();
}
//~PX_SERIALIZATION
static void FixedJointProject(const void* constantBlock, PxTransform& bodyAToWorld, PxTransform& bodyBToWorld, bool projectToA)
{
const FixedJointData &data = *reinterpret_cast<const FixedJointData*>(constantBlock);
PxTransform cA2w, cB2w, cB2cA, projected;
joint::computeDerived(data, bodyAToWorld, bodyBToWorld, cA2w, cB2w, cB2cA);
bool linearTrunc, angularTrunc;
projected.p = joint::truncateLinear(cB2cA.p, data.projectionLinearTolerance, linearTrunc);
projected.q = joint::truncateAngular(cB2cA.q, PxSin(data.projectionAngularTolerance/2), PxCos(data.projectionAngularTolerance/2), angularTrunc);
if(linearTrunc || angularTrunc)
joint::projectTransforms(bodyAToWorld, bodyBToWorld, cA2w, cB2w, projected, data, projectToA);
}
static void FixedJointVisualize(PxConstraintVisualizer& viz, const void* constantBlock, const PxTransform& body0Transform, const PxTransform& body1Transform, PxU32 flags)
{
if(flags & PxConstraintVisualizationFlag::eLOCAL_FRAMES)
{
const FixedJointData& data = *reinterpret_cast<const FixedJointData*>(constantBlock);
PxTransform cA2w, cB2w;
joint::computeJointFrames(cA2w, cB2w, data, body0Transform, body1Transform);
viz.visualizeJointFrames(cA2w, cB2w);
}
}
static PxU32 FixedJointSolverPrep(Px1DConstraint* constraints,
PxVec3& body0WorldOffset,
PxU32 /*maxConstraints*/,
PxConstraintInvMassScale& invMassScale,
const void* constantBlock,
const PxTransform& bA2w,
const PxTransform& bB2w,
bool /*useExtendedLimits*/,
PxVec3& cA2wOut, PxVec3& cB2wOut)
{
const FixedJointData& data = *reinterpret_cast<const FixedJointData*>(constantBlock);
PxTransform cA2w, cB2w;
joint::ConstraintHelper ch(constraints, invMassScale, cA2w, cB2w, body0WorldOffset, data, bA2w, bB2w);
if (cA2w.q.dot(cB2w.q)<0.0f) // minimum dist quat (equiv to flipping cB2bB.q, which we don't use anywhere)
cB2w.q = -cB2w.q;
PxVec3 ra, rb;
ch.prepareLockedAxes(cA2w.q, cB2w.q, cA2w.transformInv(cB2w.p), 7, 7, ra, rb);
cA2wOut = ra + bA2w.p;
cB2wOut = rb + bB2w.p;
return ch.getCount();
}
PxConstraintShaderTable Ext::FixedJoint::sShaders = { FixedJointSolverPrep, FixedJointProject, FixedJointVisualize, PxConstraintFlag::Enum(0) };

View File

@ -0,0 +1,118 @@
//
// 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-2021 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 NP_FIXEDJOINTCONSTRAINT_H
#define NP_FIXEDJOINTCONSTRAINT_H
#include "extensions/PxFixedJoint.h"
#include "ExtJoint.h"
#include "CmUtils.h"
namespace physx
{
struct PxFixedJointGeneratedValues;
namespace Ext
{
struct FixedJointData : public JointData
{
//= 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 projectionLinearTolerance;
PxReal projectionAngularTolerance;
};
typedef Joint<PxFixedJoint, PxFixedJointGeneratedValues> FixedJointT;
class FixedJoint : public FixedJointT
{
//= 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:
// PX_SERIALIZATION
FixedJoint(PxBaseFlags baseFlags) : FixedJointT(baseFlags) {}
virtual void exportExtraData(PxSerializationContext& context) const;
void importExtraData(PxDeserializationContext& context);
void resolveReferences(PxDeserializationContext& context);
static FixedJoint* createObject(PxU8*& address, PxDeserializationContext& context);
static void getBinaryMetaData(PxOutputStream& stream);
//~PX_SERIALIZATION
// PxFixedJoint
virtual void setProjectionLinearTolerance(PxReal tolerance);
virtual PxReal getProjectionLinearTolerance() const;
virtual void setProjectionAngularTolerance(PxReal tolerance);
virtual PxReal getProjectionAngularTolerance() const;
//~PxFixedJoint
FixedJoint(const PxTolerancesScale& /*scale*/, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1) :
FixedJointT(PxJointConcreteType::eFIXED, PxBaseFlag::eOWNS_MEMORY | PxBaseFlag::eIS_RELEASABLE, actor0, localFrame0, actor1, localFrame1, sizeof(FixedJointData), "FixedJointData")
{
FixedJointData* data = static_cast<FixedJointData*>(mData);
data->projectionLinearTolerance = 1e10f;
data->projectionAngularTolerance = PxPi;
}
bool attach(PxPhysics &physics, PxRigidActor* actor0, PxRigidActor* actor1);
static const PxConstraintShaderTable& getConstraintShaderTable() { return sShaders; }
virtual PxConstraintSolverPrep getPrep() const { return sShaders.solverPrep; }
private:
static PxConstraintShaderTable sShaders;
PX_FORCE_INLINE FixedJointData& data() const
{
return *static_cast<FixedJointData*>(mData);
}
};
} // namespace Ext
namespace Ext
{
// global function to share the joint shaders with API capture
extern "C" const PxConstraintShaderTable* GetFixedJointShaderTable();
}
}
#endif

View File

@ -0,0 +1,404 @@
//
// 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-2021 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_INERTIATENSOR_H
#define PX_PHYSICS_EXTENSIONS_INERTIATENSOR_H
#include "foundation/PxMat33.h"
#include "foundation/PxMathUtils.h"
#include "CmPhysXCommon.h"
#include "PsMathUtils.h"
namespace physx
{
namespace Ext
{
class InertiaTensorComputer
{
public:
InertiaTensorComputer(bool initTozero = true);
InertiaTensorComputer(const PxMat33& inertia, const PxVec3& com, PxReal mass);
~InertiaTensorComputer();
PX_INLINE void zero(); //sets to zero mass
PX_INLINE void setDiagonal(PxReal mass, const PxVec3& diagonal); //sets as a diagonal tensor
PX_INLINE void rotate(const PxMat33& rot); //rotates the mass
void translate(const PxVec3& t); //translates the mass
PX_INLINE void transform(const PxTransform& transform); //transforms the mass
PX_INLINE void scaleDensity(PxReal densityScale); //scales by a density factor
PX_INLINE void add(const InertiaTensorComputer& it); //adds a mass
PX_INLINE void center(); //recenters inertia around center of mass
void setBox(const PxVec3& halfWidths); //sets as an axis aligned box
PX_INLINE void setBox(const PxVec3& halfWidths, const PxTransform* pose); //sets as an oriented box
void setSphere(PxReal radius);
PX_INLINE void setSphere(PxReal radius, const PxTransform* pose);
void setCylinder(int dir, PxReal r, PxReal l);
PX_INLINE void setCylinder(int dir, PxReal r, PxReal l, const PxTransform* pose);
void setCapsule(int dir, PxReal r, PxReal l);
PX_INLINE void setCapsule(int dir, PxReal r, PxReal l, const PxTransform* pose);
void addCapsule(PxReal density, int dir, PxReal r, PxReal l, const PxTransform* pose = 0);
void setEllipsoid(PxReal rx, PxReal ry, PxReal rz);
PX_INLINE void setEllipsoid(PxReal rx, PxReal ry, PxReal rz, const PxTransform* pose);
PX_INLINE PxVec3 getCenterOfMass() const { return mG; }
PX_INLINE PxReal getMass() const { return mMass; }
PX_INLINE PxMat33 getInertia() const { return mI; }
private:
PxMat33 mI;
PxVec3 mG;
PxReal mMass;
};
//--------------------------------------------------------------
//
// Helper routines
//
//--------------------------------------------------------------
// Special version allowing 2D quads
PX_INLINE PxReal volume(const PxVec3& extents)
{
PxReal v = 1.0f;
if(extents.x != 0.0f) v*=extents.x;
if(extents.y != 0.0f) v*=extents.y;
if(extents.z != 0.0f) v*=extents.z;
return v;
}
// Sphere
PX_INLINE PxReal computeSphereRatio(PxReal radius) { return (4.0f/3.0f) * PxPi * radius * radius * radius; }
PxReal computeSphereMass(PxReal radius, PxReal density) { return density * computeSphereRatio(radius); }
PxReal computeSphereDensity(PxReal radius, PxReal mass) { return mass / computeSphereRatio(radius); }
// Box
PX_INLINE PxReal computeBoxRatio(const PxVec3& extents) { return volume(extents); }
PxReal computeBoxMass(const PxVec3& extents, PxReal density) { return density * computeBoxRatio(extents); }
PxReal computeBoxDensity(const PxVec3& extents, PxReal mass) { return mass / computeBoxRatio(extents); }
// Ellipsoid
PX_INLINE PxReal computeEllipsoidRatio(const PxVec3& extents) { return (4.0f/3.0f) * PxPi * volume(extents); }
PxReal computeEllipsoidMass(const PxVec3& extents, PxReal density) { return density * computeEllipsoidRatio(extents); }
PxReal computeEllipsoidDensity(const PxVec3& extents, PxReal mass) { return mass / computeEllipsoidRatio(extents); }
// Cylinder
PX_INLINE PxReal computeCylinderRatio(PxReal r, PxReal l) { return PxPi * r * r * (2.0f*l); }
PxReal computeCylinderMass(PxReal r, PxReal l, PxReal density) { return density * computeCylinderRatio(r, l); }
PxReal computeCylinderDensity(PxReal r, PxReal l, PxReal mass) { return mass / computeCylinderRatio(r, l); }
// Capsule
PX_INLINE PxReal computeCapsuleRatio(PxReal r, PxReal l) { return computeSphereRatio(r) + computeCylinderRatio(r, l);}
PxReal computeCapsuleMass(PxReal r, PxReal l, PxReal density) { return density * computeCapsuleRatio(r, l); }
PxReal computeCapsuleDensity(PxReal r, PxReal l, PxReal mass) { return mass / computeCapsuleRatio(r, l); }
// Cone
PX_INLINE PxReal computeConeRatio(PxReal r, PxReal l) { return PxPi * r * r * PxAbs(l)/3.0f; }
PxReal computeConeMass(PxReal r, PxReal l, PxReal density) { return density * computeConeRatio(r, l); }
PxReal computeConeDensity(PxReal r, PxReal l, PxReal mass) { return mass / computeConeRatio(r, l); }
void computeBoxInertiaTensor(PxVec3& inertia, PxReal mass, PxReal xlength, PxReal ylength, PxReal zlength);
void computeSphereInertiaTensor(PxVec3& inertia, PxReal mass, PxReal radius, bool hollow);
bool jacobiTransform(PxI32 n, PxF64 a[], PxF64 w[]);
bool diagonalizeInertiaTensor(const PxMat33& denseInertia, PxVec3& diagonalInertia, PxMat33& rotation);
} // namespace Ext
void Ext::computeBoxInertiaTensor(PxVec3& inertia, PxReal mass, PxReal xlength, PxReal ylength, PxReal zlength)
{
//to model a hollow block, one would have to multiply coeff by up to two.
const PxReal coeff = mass/12;
inertia.x = coeff * (ylength*ylength + zlength*zlength);
inertia.y = coeff * (xlength*xlength + zlength*zlength);
inertia.z = coeff * (xlength*xlength + ylength*ylength);
PX_ASSERT(inertia.x != 0.0f);
PX_ASSERT(inertia.y != 0.0f);
PX_ASSERT(inertia.z != 0.0f);
PX_ASSERT(inertia.isFinite());
}
void Ext::computeSphereInertiaTensor(PxVec3& inertia, PxReal mass, PxReal radius, bool hollow)
{
inertia.x = mass * radius * radius;
if (hollow)
inertia.x *= PxReal(2 / 3.0);
else
inertia.x *= PxReal(2 / 5.0);
inertia.z = inertia.y = inertia.x;
PX_ASSERT(inertia.isFinite());
}
//--------------------------------------------------------------
//
// InertiaTensorComputer implementation
//
//--------------------------------------------------------------
Ext::InertiaTensorComputer::InertiaTensorComputer(bool initTozero)
{
if (initTozero)
zero();
}
Ext::InertiaTensorComputer::InertiaTensorComputer(const PxMat33& inertia, const PxVec3& com, PxReal mass) :
mI(inertia),
mG(com),
mMass(mass)
{
}
Ext::InertiaTensorComputer::~InertiaTensorComputer()
{
//nothing
}
PX_INLINE void Ext::InertiaTensorComputer::zero()
{
mMass = 0.0f;
mI = PxMat33(PxZero);
mG = PxVec3(0);
}
PX_INLINE void Ext::InertiaTensorComputer::setDiagonal(PxReal mass, const PxVec3& diag)
{
mMass = mass;
mI = PxMat33::createDiagonal(diag);
mG = PxVec3(0);
PX_ASSERT(mI.column0.isFinite() && mI.column1.isFinite() && mI.column2.isFinite());
PX_ASSERT(PxIsFinite(mMass));
}
void Ext::InertiaTensorComputer::setBox(const PxVec3& halfWidths)
{
// Setup inertia tensor for a cube with unit density
const PxReal mass = 8.0f * computeBoxRatio(halfWidths);
const PxReal s =(1.0f/3.0f) * mass;
const PxReal x = halfWidths.x*halfWidths.x;
const PxReal y = halfWidths.y*halfWidths.y;
const PxReal z = halfWidths.z*halfWidths.z;
setDiagonal(mass, PxVec3(y+z, z+x, x+y) * s);
}
PX_INLINE void Ext::InertiaTensorComputer::rotate(const PxMat33& rot)
{
//well known inertia tensor rotation expression is: RIR' -- this could be optimized due to symmetry, see code to do that in Body::updateGlobalInverseInertia
mI = rot * mI * rot.getTranspose();
PX_ASSERT(mI.column0.isFinite() && mI.column1.isFinite() && mI.column2.isFinite());
//com also needs to be rotated
mG = rot * mG;
PX_ASSERT(mG.isFinite());
}
void Ext::InertiaTensorComputer::translate(const PxVec3& t)
{
if (!t.isZero()) //its common for this to be zero
{
PxMat33 t1, t2;
t1.column0 = PxVec3(0, mG.z, -mG.y);
t1.column1 = PxVec3(-mG.z, 0, mG.x);
t1.column2 = PxVec3(mG.y, -mG.x, 0);
PxVec3 sum = mG + t;
if (sum.isZero())
{
mI += (t1 * t1)*mMass;
}
else
{
t2.column0 = PxVec3(0, sum.z, -sum.y);
t2.column1 = PxVec3(-sum.z, 0, sum.x);
t2.column2 = PxVec3(sum.y, -sum.x, 0);
mI += (t1 * t1 - t2 * t2)*mMass;
}
//move center of mass
mG += t;
PX_ASSERT(mI.column0.isFinite() && mI.column1.isFinite() && mI.column2.isFinite());
PX_ASSERT(mG.isFinite());
}
}
PX_INLINE void Ext::InertiaTensorComputer::transform(const PxTransform& transform)
{
rotate(PxMat33(transform.q));
translate(transform.p);
}
PX_INLINE void Ext::InertiaTensorComputer::setBox(const PxVec3& halfWidths, const PxTransform* pose)
{
setBox(halfWidths);
if (pose)
transform(*pose);
}
PX_INLINE void Ext::InertiaTensorComputer::scaleDensity(PxReal densityScale)
{
mI *= densityScale;
mMass *= densityScale;
PX_ASSERT(mI.column0.isFinite() && mI.column1.isFinite() && mI.column2.isFinite());
PX_ASSERT(PxIsFinite(mMass));
}
PX_INLINE void Ext::InertiaTensorComputer::add(const InertiaTensorComputer& it)
{
const PxReal TotalMass = mMass + it.mMass;
mG = (mG * mMass + it.mG * it.mMass) / TotalMass;
mMass = TotalMass;
mI += it.mI;
PX_ASSERT(mI.column0.isFinite() && mI.column1.isFinite() && mI.column2.isFinite());
PX_ASSERT(mG.isFinite());
PX_ASSERT(PxIsFinite(mMass));
}
PX_INLINE void Ext::InertiaTensorComputer::center()
{
PxVec3 center = -mG;
translate(center);
}
void Ext::InertiaTensorComputer::setSphere(PxReal radius)
{
// Compute mass of the sphere
const PxReal m = computeSphereRatio(radius);
// Compute moment of inertia
const PxReal s = m * radius * radius * (2.0f/5.0f);
setDiagonal(m,PxVec3(s,s,s));
}
PX_INLINE void Ext::InertiaTensorComputer::setSphere(PxReal radius, const PxTransform* pose)
{
setSphere(radius);
if (pose)
transform(*pose);
}
void Ext::InertiaTensorComputer::setCylinder(int dir, PxReal r, PxReal l)
{
// Compute mass of cylinder
const PxReal m = computeCylinderRatio(r, l);
const PxReal i1 = r*r*m/2.0f;
const PxReal i2 = (3.0f*r*r+4.0f*l*l)*m/12.0f;
switch(dir)
{
case 0: setDiagonal(m,PxVec3(i1,i2,i2)); break;
case 1: setDiagonal(m,PxVec3(i2,i1,i2)); break;
default: setDiagonal(m,PxVec3(i2,i2,i1)); break;
}
}
PX_INLINE void Ext::InertiaTensorComputer::setCylinder(int dir, PxReal r, PxReal l, const PxTransform* pose)
{
setCylinder(dir, r, l);
if (pose)
transform(*pose);
}
void Ext::InertiaTensorComputer::setCapsule(int dir, PxReal r, PxReal l)
{
// Compute mass of capsule
const PxReal m = computeCapsuleRatio(r, l);
const PxReal t = PxPi * r * r;
const PxReal i1 = t * ((r*r*r * 8.0f/15.0f) + (l*r*r));
const PxReal i2 = t * ((r*r*r * 8.0f/15.0f) + (l*r*r * 3.0f/2.0f) + (l*l*r * 4.0f/3.0f) + (l*l*l * 2.0f/3.0f));
switch(dir)
{
case 0: setDiagonal(m,PxVec3(i1,i2,i2)); break;
case 1: setDiagonal(m,PxVec3(i2,i1,i2)); break;
default: setDiagonal(m,PxVec3(i2,i2,i1)); break;
}
}
PX_INLINE void Ext::InertiaTensorComputer::setCapsule(int dir, PxReal r, PxReal l, const PxTransform* pose)
{
setCapsule(dir, r, l);
if (pose)
transform(*pose);
}
void Ext::InertiaTensorComputer::setEllipsoid(PxReal rx, PxReal ry, PxReal rz)
{
// Compute mass of ellipsoid
const PxReal m = computeEllipsoidRatio(PxVec3(rx, ry, rz));
// Compute moment of inertia
const PxReal s = m * (2.0f/5.0f);
// Setup inertia tensor for an ellipsoid centered at the origin
setDiagonal(m,PxVec3(ry*rz,rz*rx,rx*ry)*s);
}
PX_INLINE void Ext::InertiaTensorComputer::setEllipsoid(PxReal rx, PxReal ry, PxReal rz, const PxTransform* pose)
{
setEllipsoid(rx,ry,rz);
if (pose)
transform(*pose);
}
}
#endif

View File

@ -0,0 +1,126 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "ExtJoint.h"
using namespace physx;
using namespace Ext;
PxConstraint* physx::resolveConstraintPtr(PxDeserializationContext& v,
PxConstraint* old,
PxConstraintConnector* connector,
PxConstraintShaderTable &shaders)
{
v.translatePxBase(old);
PxConstraint* new_nx = static_cast<PxConstraint*>(old);
new_nx->setConstraintFunctions(*connector, shaders);
return new_nx;
}
//~PX_SERIALIZATION
static void normalToTangents(const PxVec3& n, PxVec3& t1, PxVec3& t2)
{
const PxReal m_sqrt1_2 = PxReal(0.7071067811865475244008443621048490);
if(fabsf(n.z) > m_sqrt1_2)
{
const PxReal a = n.y*n.y + n.z*n.z;
const PxReal k = PxReal(1.0)/PxSqrt(a);
t1 = PxVec3(0,-n.z*k,n.y*k);
t2 = PxVec3(a*k,-n.x*t1.z,n.x*t1.y);
}
else
{
const PxReal a = n.x*n.x + n.y*n.y;
const PxReal k = PxReal(1.0)/PxSqrt(a);
t1 = PxVec3(-n.y*k,n.x*k,0);
t2 = PxVec3(-n.z*t1.y,n.z*t1.x,a*k);
}
t1.normalize();
t2.normalize();
}
void PxSetJointGlobalFrame(PxJoint& joint, const PxVec3* wsAnchor, const PxVec3* axisIn)
{
PxRigidActor* actors[2];
joint.getActors(actors[0], actors[1]);
PxTransform localPose[2];
for(PxU32 i=0; i<2; i++)
localPose[i] = PxTransform(PxIdentity);
// 1) global anchor
if(wsAnchor)
{
//transform anchorPoint to local space
for(PxU32 i=0; i<2; i++)
localPose[i].p = actors[i] ? actors[i]->getGlobalPose().transformInv(*wsAnchor) : *wsAnchor;
}
// 2) global axis
if(axisIn)
{
PxVec3 localAxis[2], localNormal[2];
//find 2 orthogonal vectors.
//gotta do this in world space, if we choose them
//separately in local space they won't match up in worldspace.
PxVec3 axisw = *axisIn;
axisw.normalize();
PxVec3 normalw, binormalw;
::normalToTangents(axisw, binormalw, normalw);
//because axis is supposed to be the Z axis of a frame with the other two being X and Y, we need to negate
//Y to make the frame right handed. Note that the above call makes a right handed frame if we pass X --> Y,Z, so
//it need not be changed.
for(PxU32 i=0; i<2; i++)
{
if(actors[i])
{
const PxTransform& m = actors[i]->getGlobalPose();
PxMat33 mM(m.q);
localAxis[i] = mM.transformTranspose(axisw);
localNormal[i] = mM.transformTranspose(normalw);
}
else
{
localAxis[i] = axisw;
localNormal[i] = normalw;
}
PxMat33 rot(localAxis[i], localNormal[i], localAxis[i].cross(localNormal[i]));
localPose[i].q = PxQuat(rot);
localPose[i].q.normalize();
}
}
for(PxU32 i=0; i<2; i++)
joint.setLocalPose(static_cast<PxJointActorIndex::Enum>( i ), localPose[i]);
}

View File

@ -0,0 +1,619 @@
//
// 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-2021 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 NP_JOINTCONSTRAINT_H
#define NP_JOINTCONSTRAINT_H
#include "extensions/PxConstraintExt.h"
#include "PxRigidStatic.h"
#include "PxRigidDynamic.h"
#include "PxScene.h"
#include "PsAllocator.h"
#include "PsMathUtils.h"
#include "CmUtils.h"
#include "PsFoundation.h"
#include "ExtJointData.h"
#if PX_SUPPORT_PVD
#include "pvd/PxPvdSceneClient.h"
#include "ExtPvd.h"
#include "PxPvdClient.h"
#endif
// PX_SERIALIZATION
namespace physx
{
class PxDeserializationContext;
PxConstraint* resolveConstraintPtr(PxDeserializationContext& v, PxConstraint* old, PxConstraintConnector* connector, PxConstraintShaderTable& shaders);
// ~PX_SERIALIZATION
namespace Ext
{
template <class Base, class ValueStruct>
class Joint : public Base,
public PxConstraintConnector,
public shdfnd::UserAllocated
{
public:
// PX_SERIALIZATION
Joint(PxBaseFlags baseFlags) : Base(baseFlags) {}
virtual void preExportDataReset(){}
virtual void requiresObjects(PxProcessPxBaseCallback& c)
{
c.process(*mPxConstraint);
{
PxRigidActor* a0 = NULL;
PxRigidActor* a1 = NULL;
mPxConstraint->getActors(a0,a1);
if (a0)
{
c.process(*a0);
}
if (a1)
{
c.process(*a1);
}
}
}
//~PX_SERIALIZATION
#if PX_SUPPORT_PVD
// PxConstraintConnector
virtual bool updatePvdProperties(physx::pvdsdk::PvdDataStream& pvdConnection, const PxConstraint* c, PxPvdUpdateType::Enum updateType) const
{
if(updateType == PxPvdUpdateType::UPDATE_SIM_PROPERTIES)
{
Ext::Pvd::simUpdate<Base>(pvdConnection, *this);
return true;
}
else if(updateType == PxPvdUpdateType::UPDATE_ALL_PROPERTIES)
{
Ext::Pvd::updatePvdProperties<Base, ValueStruct>(pvdConnection, *this);
return true;
}
else if(updateType == PxPvdUpdateType::CREATE_INSTANCE)
{
Ext::Pvd::createPvdInstance<Base>(pvdConnection, *c, *this);
return true;
}
else if(updateType == PxPvdUpdateType::RELEASE_INSTANCE)
{
Ext::Pvd::releasePvdInstance(pvdConnection, *c, *this);
return true;
}
return false;
}
#else
virtual bool updatePvdProperties(physx::pvdsdk::PvdDataStream&, const PxConstraint*, PxPvdUpdateType::Enum) const
{
return false;
}
#endif
// PxJoint
virtual void setActors(PxRigidActor* actor0, PxRigidActor* actor1)
{
//TODO SDK-DEV
//You can get the debugger stream from the NpScene
//Ext::Pvd::setActors( stream, this, mPxConstraint, actor0, actor1 );
PX_CHECK_AND_RETURN(actor0 != actor1, "PxJoint::setActors: actors must be different");
PX_CHECK_AND_RETURN((actor0 && !actor0->is<PxRigidStatic>()) || (actor1 && !actor1->is<PxRigidStatic>()), "PxJoint::setActors: at least one actor must be non-static");
#if PX_SUPPORT_PVD
PxScene* scene = getScene();
if(scene)
{
//if pvd not connect data stream is NULL
physx::pvdsdk::PvdDataStream* conn = scene->getScenePvdClient()->getClientInternal()->getDataStream();
if( conn != NULL )
Ext::Pvd::setActors(
*conn,
*this,
*mPxConstraint,
actor0,
actor1
);
}
#endif
mPxConstraint->setActors(actor0, actor1);
mData->c2b[0] = getCom(actor0).transformInv(mLocalPose[0]);
mData->c2b[1] = getCom(actor1).transformInv(mLocalPose[1]);
mPxConstraint->markDirty();
}
// PxJoint
virtual void getActors(PxRigidActor*& actor0, PxRigidActor*& actor1) const
{
if(mPxConstraint)
mPxConstraint->getActors(actor0, actor1);
else
{
actor0 = NULL;
actor1 = NULL;
}
}
// this is the local pose relative to the actor, and we store internally the local
// pose relative to the body
// PxJoint
virtual void setLocalPose(PxJointActorIndex::Enum actor, const PxTransform& pose)
{
PX_CHECK_AND_RETURN(pose.isSane(), "PxJoint::setLocalPose: transform is invalid");
PxTransform p = pose.getNormalized();
mLocalPose[actor] = p;
mData->c2b[actor] = getCom(actor).transformInv(p);
mPxConstraint->markDirty();
}
// PxJoint
virtual PxTransform getLocalPose(PxJointActorIndex::Enum actor) const
{
return mLocalPose[actor];
}
static PxTransform getGlobalPose(const PxRigidActor* actor)
{
if(!actor)
return PxTransform(PxIdentity);
return actor->getGlobalPose();
}
static void getActorVelocity(const PxRigidActor* actor, PxVec3& linear, PxVec3& angular)
{
if(!actor || actor->is<PxRigidStatic>())
{
linear = angular = PxVec3(0.0f);
return;
}
linear = static_cast<const PxRigidBody*>(actor)->getLinearVelocity();
angular = static_cast<const PxRigidBody*>(actor)->getAngularVelocity();
}
// PxJoint
virtual PxTransform getRelativeTransform() const
{
PxRigidActor* actor0, * actor1;
mPxConstraint->getActors(actor0, actor1);
const PxTransform t0 = getGlobalPose(actor0) * mLocalPose[0];
const PxTransform t1 = getGlobalPose(actor1) * mLocalPose[1];
return t0.transformInv(t1);
}
// PxJoint
virtual PxVec3 getRelativeLinearVelocity() const
{
PxRigidActor* actor0, * actor1;
PxVec3 l0, a0, l1, a1;
mPxConstraint->getActors(actor0, actor1);
PxTransform t0 = getCom(actor0), t1 = getCom(actor1);
getActorVelocity(actor0, l0, a0);
getActorVelocity(actor1, l1, a1);
PxVec3 p0 = t0.q.rotate(mLocalPose[0].p),
p1 = t1.q.rotate(mLocalPose[1].p);
return t0.transformInv(l1 - a1.cross(p1) - l0 + a0.cross(p0));
}
// PxJoint
virtual PxVec3 getRelativeAngularVelocity() const
{
PxRigidActor* actor0, * actor1;
PxVec3 l0, a0, l1, a1;
mPxConstraint->getActors(actor0, actor1);
PxTransform t0 = getCom(actor0);
getActorVelocity(actor0, l0, a0);
getActorVelocity(actor1, l1, a1);
return t0.transformInv(a1 - a0);
}
// PxJoint
virtual void setBreakForce(PxReal force, PxReal torque)
{
PX_CHECK_AND_RETURN(PxIsFinite(force) && PxIsFinite(torque), "NpJoint::setBreakForce: invalid float");
mPxConstraint->setBreakForce(force,torque);
}
// PxJoint
virtual void getBreakForce(PxReal& force, PxReal& torque) const
{
mPxConstraint->getBreakForce(force,torque);
}
// PxJoint
virtual void setConstraintFlags(PxConstraintFlags flags)
{
mPxConstraint->setFlags(flags);
}
// PxJoint
virtual void setConstraintFlag(PxConstraintFlag::Enum flag, bool value)
{
mPxConstraint->setFlag(flag, value);
}
// PxJoint
virtual PxConstraintFlags getConstraintFlags() const
{
return mPxConstraint->getFlags();
}
// PxJoint
virtual void setInvMassScale0(PxReal invMassScale)
{
PX_CHECK_AND_RETURN(PxIsFinite(invMassScale) && invMassScale>=0, "PxJoint::setInvMassScale0: scale must be non-negative");
mData->invMassScale.linear0 = invMassScale;
mPxConstraint->markDirty();
}
// PxJoint
virtual PxReal getInvMassScale0() const
{
return mData->invMassScale.linear0;
}
// PxJoint
virtual void setInvInertiaScale0(PxReal invInertiaScale)
{
PX_CHECK_AND_RETURN(PxIsFinite(invInertiaScale) && invInertiaScale>=0, "PxJoint::setInvInertiaScale0: scale must be non-negative");
mData->invMassScale.angular0 = invInertiaScale;
mPxConstraint->markDirty();
}
// PxJoint
virtual PxReal getInvInertiaScale0() const
{
return mData->invMassScale.angular0;
}
// PxJoint
virtual void setInvMassScale1(PxReal invMassScale)
{
PX_CHECK_AND_RETURN(PxIsFinite(invMassScale) && invMassScale>=0, "PxJoint::setInvMassScale1: scale must be non-negative");
mData->invMassScale.linear1 = invMassScale;
mPxConstraint->markDirty();
}
// PxJoint
virtual PxReal getInvMassScale1() const
{
return mData->invMassScale.linear1;
}
// PxJoint
virtual void setInvInertiaScale1(PxReal invInertiaScale)
{
PX_CHECK_AND_RETURN(PxIsFinite(invInertiaScale) && invInertiaScale>=0, "PxJoint::setInvInertiaScale: scale must be non-negative");
mData->invMassScale.angular1 = invInertiaScale;
mPxConstraint->markDirty();
}
// PxJoint
virtual PxReal getInvInertiaScale1() const
{
return mData->invMassScale.angular1;
}
// PxJoint
virtual PxConstraint* getConstraint() const
{
return mPxConstraint;
}
// PxJoint
virtual void setName(const char* name)
{
mName = name;
}
// PxJoint
virtual const char* getName() const
{
return mName;
}
// PxJoint
virtual void release()
{
mPxConstraint->release();
}
// PxJoint
virtual PxScene* getScene() const
{
return mPxConstraint ? mPxConstraint->getScene() : NULL;
}
// PxConstraintConnector
virtual void onComShift(PxU32 actor)
{
mData->c2b[actor] = getCom(actor).transformInv(mLocalPose[actor]);
markDirty();
}
// PxConstraintConnector
virtual void onOriginShift(const PxVec3& shift)
{
PxRigidActor* a[2];
mPxConstraint->getActors(a[0], a[1]);
if (!a[0])
{
mLocalPose[0].p -= shift;
mData->c2b[0].p -= shift;
markDirty();
}
else if (!a[1])
{
mLocalPose[1].p -= shift;
mData->c2b[1].p -= shift;
markDirty();
}
}
// PxConstraintConnector
virtual void* prepareData()
{
return mData;
}
// PxConstraintConnector
virtual void* getExternalReference(PxU32& typeID)
{
typeID = PxConstraintExtIDs::eJOINT;
return static_cast<PxJoint*>( this );
}
// PxConstraintConnector
virtual PxBase* getSerializable()
{
return this;
}
// PxConstraintConnector
virtual void onConstraintRelease()
{
PX_FREE_AND_RESET(mData);
delete this;
}
// PxConstraintConnector
virtual const void* getConstantBlock() const
{
return mData;
}
private:
PxTransform getCom(PxU32 index) const
{
PxRigidActor* a[2];
mPxConstraint->getActors(a[0],a[1]);
return getCom(a[index]);
}
PxTransform getCom(PxRigidActor* actor) const
{
if (!actor)
return PxTransform(PxIdentity);
else if (actor->getType() == PxActorType::eRIGID_DYNAMIC || actor->getType() == PxActorType::eARTICULATION_LINK)
return static_cast<PxRigidBody*>(actor)->getCMassLocalPose();
else
{
PX_ASSERT(actor->getType() == PxActorType::eRIGID_STATIC);
return static_cast<PxRigidStatic*>(actor)->getGlobalPose().getInverse();
}
}
protected:
Joint(PxType concreteType, PxBaseFlags baseFlags, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1, PxU32 size, const char* name) :
Base (concreteType, baseFlags),
mName (NULL),
mPxConstraint (NULL)
{
PX_UNUSED(name);
Base::userData = NULL;
JointData* data = reinterpret_cast<JointData*>(PX_ALLOC(size, name));
Cm::markSerializedMem(data, size);
mLocalPose[0] = localFrame0.getNormalized();
mLocalPose[1] = localFrame1.getNormalized();
data->c2b[0] = getCom(actor0).transformInv(localFrame0);
data->c2b[1] = getCom(actor1).transformInv(localFrame1);
data->invMassScale.linear0 = 1.0f;
data->invMassScale.angular0 = 1.0f;
data->invMassScale.linear1 = 1.0f;
data->invMassScale.angular1 = 1.0f;
mData = data;
}
virtual ~Joint()
{
if(Base::getBaseFlags() & PxBaseFlag::eOWNS_MEMORY)
PX_FREE_AND_RESET(mData);
}
PX_FORCE_INLINE void markDirty()
{
mPxConstraint->markDirty();
}
PX_FORCE_INLINE PxConstraintConnector* getConnector()
{
return this;
}
PX_FORCE_INLINE PxConstraint* getPxConstraint()
{
return mPxConstraint;
}
PX_FORCE_INLINE void setPxConstraint(PxConstraint* pxConstraint)
{
mPxConstraint = pxConstraint;
}
void wakeUpActors()
{
PxRigidActor* a[2];
mPxConstraint->getActors(a[0], a[1]);
for(PxU32 i = 0; i < 2; i++)
{
if(a[i] && a[i]->getScene() && a[i]->getType() == PxActorType::eRIGID_DYNAMIC)
{
PxRigidDynamic* rd = static_cast<PxRigidDynamic*>(a[i]);
if(!(rd->getRigidBodyFlags() & PxRigidBodyFlag::eKINEMATIC))
{
const PxScene* scene = rd->getScene();
const PxReal wakeCounterResetValue = scene->getWakeCounterResetValue();
PxReal wakeCounter = rd->getWakeCounter();
bool needsWakingUp = rd->isSleeping();
if (wakeCounter < wakeCounterResetValue)
{
wakeCounter = wakeCounterResetValue;
needsWakingUp = true;
}
if (needsWakingUp)
{
rd->wakeUp();
rd->setWakeCounter(wakeCounter);
}
}
}
}
}
PX_FORCE_INLINE PxQuat getTwistOrSwing(bool needTwist) const
{
const PxQuat q = getRelativeTransform().q;
// PT: TODO: we don't need to compute both quats here
PxQuat swing, twist;
Ps::separateSwingTwist(q, swing, twist);
return needTwist ? twist : swing;
}
PxReal getTwistAngle_Internal() const
{
const PxQuat twist = getTwistOrSwing(true);
// PT: the angle-axis formulation creates the quat like this:
//
// const float a = angleRadians * 0.5f;
// const float s = PxSin(a);
// w = PxCos(a);
// x = unitAxis.x * s;
// y = unitAxis.y * s;
// z = unitAxis.z * s;
//
// With the twist axis = (1;0;0) this gives:
//
// w = PxCos(angleRadians * 0.5f);
// x = PxSin(angleRadians * 0.5f);
// y = 0.0f;
// z = 0.0f;
//
// Thus the quat's "getAngle" function returns:
//
// angle = PxAcos(w) * 2.0f;
//
// PxAcos will return an angle between 0 and PI in radians, so "getAngle" will return an angle between 0 and PI*2.
PxReal angle = twist.getAngle();
if(twist.x<0.0f)
angle = -angle;
return angle;
}
PxReal getSwingYAngle_Internal() const
{
PxQuat swing = getTwistOrSwing(false);
if(swing.w < 0.0f) // choose the shortest rotation
swing = -swing;
const PxReal angle = Ps::computeSwingAngle(swing.y, swing.w);
PX_ASSERT(angle>-PxPi && angle<=PxPi); // since |y| < w+1, the atan magnitude is < PI/4
return angle;
}
PxReal getSwingZAngle_Internal() const
{
PxQuat swing = getTwistOrSwing(false);
if(swing.w < 0.0f) // choose the shortest rotation
swing = -swing;
const PxReal angle = Ps::computeSwingAngle(swing.z, swing.w);
PX_ASSERT(angle>-PxPi && angle <= PxPi); // since |y| < w+1, the atan magnitude is < PI/4
return angle;
}
const char* mName;
PxTransform mLocalPose[2];
PxConstraint* mPxConstraint;
JointData* mData;
};
PX_FORCE_INLINE bool isLimitActive(const PxJointLimitParameters& limit, PxReal pad, PxReal angle, PxReal low, PxReal high)
{
PX_ASSERT(low<high);
if(limit.isSoft())
pad = 0.0f;
bool active = false;
if(angle < low + pad)
active = true;
if(angle > high - pad)
active = true;
return active;
}
} // namespace Ext
}
#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-2021 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 EXT_JOINT_DATA_H
#define EXT_JOINT_DATA_H
#include "extensions/PxJointLimit.h"
namespace physx
{
namespace Ext
{
struct JointData
{
//= 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.
//==================================================================================================
PxConstraintInvMassScale invMassScale; //16
PxTransform c2b[2]; //72
PxU32 pading[2]; //80
protected:
~JointData() {}
};
} // namespace Ext
}
#endif

View File

@ -0,0 +1,65 @@
//
// 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-2021 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 EXT_JOINT_META_DATA_EXTENSIONS_H
#define EXT_JOINT_META_DATA_EXTENSIONS_H
#include "PvdMetaDataExtensions.h"
namespace physx
{
namespace pvdsdk
{
struct PxExtensionPvdOnlyProperties
{
enum Enum
{
FirstProp = PxExtensionsPropertyInfoName::LastPxPropertyInfoName,
DEFINE_ENUM_RANGE( PxJoint_Actors, 2 ),
DEFINE_ENUM_RANGE( PxJoint_BreakForce, 2 ),
DEFINE_ENUM_RANGE( PxD6Joint_DriveVelocity, 2 ),
DEFINE_ENUM_RANGE( PxD6Joint_Motion, PxD6Axis::eCOUNT ),
DEFINE_ENUM_RANGE( PxD6Joint_Drive, PxD6Drive::eCOUNT * ( PxExtensionsPropertyInfoName::PxD6JointDrive_PropertiesStop - PxExtensionsPropertyInfoName::PxD6JointDrive_PropertiesStart ) ),
DEFINE_ENUM_RANGE( PxD6Joint_LinearLimit, 100 ),
DEFINE_ENUM_RANGE( PxD6Joint_SwingLimit, 100 ),
DEFINE_ENUM_RANGE( PxD6Joint_TwistLimit, 100 ),
DEFINE_ENUM_RANGE( PxPrismaticJoint_Limit, 100 ),
DEFINE_ENUM_RANGE( PxRevoluteJoint_Limit, 100 ),
DEFINE_ENUM_RANGE( PxSphericalJoint_LimitCone, 100 ),
DEFINE_ENUM_RANGE( PxJoint_LocalPose, 2 )
};
};
}
}
#endif

View File

@ -0,0 +1,446 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "foundation/PxIO.h"
#include "common/PxMetaData.h"
#include "extensions/PxJoint.h"
#include "ExtJoint.h"
#include "ExtD6Joint.h"
#include "ExtFixedJoint.h"
#include "ExtSphericalJoint.h"
#include "ExtDistanceJoint.h"
#include "ExtContactJoint.h"
#include "ExtSphericalJoint.h"
#include "ExtRevoluteJoint.h"
#include "ExtPrismaticJoint.h"
#include "serialization/SnSerializationRegistry.h"
#include "serialization/Binary/SnSerializationContext.h"
using namespace physx;
using namespace Cm;
using namespace Ext;
///////////////////////////////////////////////////////////////////////////////
static void getBinaryMetaData_JointData(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_CLASS(stream, JointData)
PX_DEF_BIN_METADATA_ITEMS_AUTO(stream, JointData, PxTransform, c2b, 0)
#ifdef EXPLICIT_PADDING_METADATA
PX_DEF_BIN_METADATA_ITEM(stream, JointData, PxU32, paddingFromFlags, PxMetaDataFlag::ePADDING)
#endif
PX_DEF_BIN_METADATA_ITEM(stream, JointData, PxConstraintInvMassScale, invMassScale, 0)
}
static void getBinaryMetaData_PxD6JointDrive(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_TYPEDEF(stream, PxD6JointDriveFlags, PxU32)
PX_DEF_BIN_METADATA_CLASS(stream, PxD6JointDrive)
PX_DEF_BIN_METADATA_ITEM(stream, PxD6JointDrive, PxReal, stiffness, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PxD6JointDrive, PxReal, damping, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PxD6JointDrive, PxReal, forceLimit, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PxD6JointDrive, PxD6JointDriveFlags, flags, 0)
}
static void getBinaryMetaData_PxJointLimitParameters(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_CLASS(stream, PxJointLimitParameters)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointLimitParameters, PxReal, restitution, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointLimitParameters, PxReal, bounceThreshold, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointLimitParameters, PxReal, stiffness, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointLimitParameters, PxReal, damping, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointLimitParameters, PxReal, contactDistance, 0)
}
static void getBinaryMetaData_PxJointLinearLimit(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_CLASS(stream, PxJointLinearLimit)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, PxJointLinearLimit, PxJointLimitParameters)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointLinearLimit, PxReal, value, 0)
}
static void getBinaryMetaData_PxJointLinearLimitPair(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_CLASS(stream, PxJointLinearLimitPair)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, PxJointLinearLimitPair, PxJointLimitParameters)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointLinearLimitPair, PxReal, upper, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointLinearLimitPair, PxReal, lower, 0)
}
static void getBinaryMetaData_PxJointAngularLimitPair(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_CLASS(stream, PxJointAngularLimitPair)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, PxJointAngularLimitPair, PxJointLimitParameters)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointAngularLimitPair, PxReal, upper, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointAngularLimitPair, PxReal, lower, 0)
}
static void getBinaryMetaData_PxJointLimitCone(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_CLASS(stream, PxJointLimitCone)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, PxJointLimitCone, PxJointLimitParameters)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointLimitCone, PxReal, yAngle, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointLimitCone, PxReal, zAngle, 0)
}
static void getBinaryMetaData_PxJointLimitPyramid(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_CLASS(stream, PxJointLimitPyramid)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, PxJointLimitPyramid, PxJointLimitParameters)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointLimitPyramid, PxReal, yAngleMin, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointLimitPyramid, PxReal, yAngleMax, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointLimitPyramid, PxReal, zAngleMin, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PxJointLimitPyramid, PxReal, zAngleMax, 0)
}
void PxJoint::getBinaryMetaData(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_VCLASS(stream, PxJoint)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, PxJoint, PxBase)
PX_DEF_BIN_METADATA_ITEM(stream, PxJoint, void, userData, PxMetaDataFlag::ePTR)
}
///////////////////////////////////////////////////////////////////////////////
static void getBinaryMetaData_RevoluteJointData(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_TYPEDEF(stream, PxRevoluteJointFlags, PxU16)
PX_DEF_BIN_METADATA_CLASS(stream, RevoluteJointData)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, RevoluteJointData, JointData)
PX_DEF_BIN_METADATA_ITEM(stream, RevoluteJointData, PxReal, driveVelocity, 0)
PX_DEF_BIN_METADATA_ITEM(stream, RevoluteJointData, PxReal, driveForceLimit, 0)
PX_DEF_BIN_METADATA_ITEM(stream, RevoluteJointData, PxReal, driveGearRatio, 0)
PX_DEF_BIN_METADATA_ITEM(stream, RevoluteJointData, PxJointAngularLimitPair,limit, 0)
PX_DEF_BIN_METADATA_ITEM(stream, RevoluteJointData, PxReal, projectionLinearTolerance, 0)
PX_DEF_BIN_METADATA_ITEM(stream, RevoluteJointData, PxReal, projectionAngularTolerance, 0)
PX_DEF_BIN_METADATA_ITEM(stream, RevoluteJointData, PxRevoluteJointFlags, jointFlags, 0)
#ifdef EXPLICIT_PADDING_METADATA
PX_DEF_BIN_METADATA_ITEM(stream, RevoluteJointData, PxU16, paddingFromFlags, PxMetaDataFlag::ePADDING)
#endif
}
void RevoluteJoint::getBinaryMetaData(PxOutputStream& stream)
{
getBinaryMetaData_RevoluteJointData(stream);
PX_DEF_BIN_METADATA_VCLASS(stream, RevoluteJoint)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, RevoluteJoint, PxJoint)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, RevoluteJoint, PxConstraintConnector)
PX_DEF_BIN_METADATA_ITEM(stream, RevoluteJoint, char, mName, PxMetaDataFlag::ePTR)
PX_DEF_BIN_METADATA_ITEMS_AUTO(stream, RevoluteJoint, PxTransform, mLocalPose, 0)
PX_DEF_BIN_METADATA_ITEM(stream, RevoluteJoint, PxConstraint, mPxConstraint, PxMetaDataFlag::ePTR)
PX_DEF_BIN_METADATA_ITEM(stream, RevoluteJoint, JointData, mData, PxMetaDataFlag::ePTR)
//------ Extra-data ------
PX_DEF_BIN_METADATA_EXTRA_ITEM(stream, RevoluteJoint, RevoluteJointData, mData, PX_SERIAL_ALIGN)
PX_DEF_BIN_METADATA_EXTRA_NAME(stream, RevoluteJoint, mName, 0)
}
///////////////////////////////////////////////////////////////////////////////
static void getBinaryMetaData_SphericalJointData(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_TYPEDEF(stream, PxSphericalJointFlags, PxU16)
PX_DEF_BIN_METADATA_CLASS(stream, SphericalJointData)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, SphericalJointData, JointData)
PX_DEF_BIN_METADATA_ITEM(stream, SphericalJointData, PxJointLimitCone, limit, 0)
PX_DEF_BIN_METADATA_ITEM(stream, SphericalJointData, PxReal, projectionLinearTolerance, 0)
PX_DEF_BIN_METADATA_ITEM(stream, SphericalJointData, PxSphericalJointFlags, jointFlags, 0)
#ifdef EXPLICIT_PADDING_METADATA
PX_DEF_BIN_METADATA_ITEM(stream, SphericalJointData, PxU16, paddingFromFlags, PxMetaDataFlag::ePADDING)
#endif
}
void SphericalJoint::getBinaryMetaData(PxOutputStream& stream)
{
getBinaryMetaData_SphericalJointData(stream);
PX_DEF_BIN_METADATA_VCLASS(stream, SphericalJoint)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, SphericalJoint, PxJoint)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, SphericalJoint, PxConstraintConnector)
PX_DEF_BIN_METADATA_ITEM(stream, SphericalJoint, char, mName, PxMetaDataFlag::ePTR)
PX_DEF_BIN_METADATA_ITEMS_AUTO(stream, SphericalJoint, PxTransform, mLocalPose, 0)
PX_DEF_BIN_METADATA_ITEM(stream, SphericalJoint, PxConstraint, mPxConstraint, PxMetaDataFlag::ePTR)
PX_DEF_BIN_METADATA_ITEM(stream, SphericalJoint, JointData, mData, PxMetaDataFlag::ePTR)
//------ Extra-data ------
PX_DEF_BIN_METADATA_EXTRA_ITEM(stream, SphericalJoint, SphericalJointData, mData, PX_SERIAL_ALIGN)
PX_DEF_BIN_METADATA_EXTRA_NAME(stream, SphericalJoint, mName, 0)
}
///////////////////////////////////////////////////////////////////////////////
static void getBinaryMetaData_DistanceJointData(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_TYPEDEF(stream, PxDistanceJointFlags, PxU16)
PX_DEF_BIN_METADATA_CLASS(stream, DistanceJointData)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, DistanceJointData, JointData)
PX_DEF_BIN_METADATA_ITEM(stream, DistanceJointData, PxReal, minDistance, 0)
PX_DEF_BIN_METADATA_ITEM(stream, DistanceJointData, PxReal, maxDistance, 0)
PX_DEF_BIN_METADATA_ITEM(stream, DistanceJointData, PxReal, tolerance, 0)
PX_DEF_BIN_METADATA_ITEM(stream, DistanceJointData, PxReal, stiffness, 0)
PX_DEF_BIN_METADATA_ITEM(stream, DistanceJointData, PxReal, damping, 0)
PX_DEF_BIN_METADATA_ITEM(stream, DistanceJointData, PxDistanceJointFlags, jointFlags, 0)
#ifdef EXPLICIT_PADDING_METADATA
PX_DEF_BIN_METADATA_ITEM(stream, DistanceJointData, PxU16, paddingFromFlags, PxMetaDataFlag::ePADDING)
#endif
}
void DistanceJoint::getBinaryMetaData(PxOutputStream& stream)
{
getBinaryMetaData_DistanceJointData(stream);
PX_DEF_BIN_METADATA_VCLASS(stream, DistanceJoint)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, DistanceJoint, PxJoint)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, DistanceJoint, PxConstraintConnector)
PX_DEF_BIN_METADATA_ITEM(stream, DistanceJoint, char, mName, PxMetaDataFlag::ePTR)
PX_DEF_BIN_METADATA_ITEMS_AUTO(stream, DistanceJoint, PxTransform, mLocalPose, 0)
PX_DEF_BIN_METADATA_ITEM(stream, DistanceJoint, PxConstraint, mPxConstraint, PxMetaDataFlag::ePTR)
PX_DEF_BIN_METADATA_ITEM(stream, DistanceJoint, JointData, mData, PxMetaDataFlag::ePTR)
//------ Extra-data ------
PX_DEF_BIN_METADATA_EXTRA_ITEM(stream, DistanceJoint, DistanceJointData, mData, PX_SERIAL_ALIGN)
PX_DEF_BIN_METADATA_EXTRA_NAME(stream, DistanceJoint, mName, 0)
}
///////////////////////////////////////////////////////////////////////////////
static void getBinaryMetaData_D6JointData(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_TYPEDEF(stream, PxD6Motion::Enum, PxU32)
PX_DEF_BIN_METADATA_CLASS(stream, D6JointData)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, D6JointData, JointData)
PX_DEF_BIN_METADATA_ITEMS_AUTO(stream, D6JointData, PxD6Motion::Enum, motion, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxJointLinearLimit, distanceLimit, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxJointLinearLimitPair, linearLimitX, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxJointLinearLimitPair, linearLimitY, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxJointLinearLimitPair, linearLimitZ, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxJointAngularLimitPair, twistLimit, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxJointLimitCone, swingLimit, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxJointLimitPyramid, pyramidSwingLimit, 0)
PX_DEF_BIN_METADATA_ITEMS_AUTO(stream, D6JointData, PxD6JointDrive, drive, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxTransform, drivePosition, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxVec3, driveLinearVelocity, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxVec3, driveAngularVelocity, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxU32, locked, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxU32, limited, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxU32, driving, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxReal, distanceMinDist, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxReal, projectionLinearTolerance, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, PxReal, projectionAngularTolerance, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, bool, mUseDistanceLimit, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, bool, mUseNewLinearLimits, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, bool, mUseConeLimit, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6JointData, bool, mUsePyramidLimits, 0)
}
void D6Joint::getBinaryMetaData(PxOutputStream& stream)
{
getBinaryMetaData_D6JointData(stream);
PX_DEF_BIN_METADATA_VCLASS(stream, D6Joint)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, D6Joint, PxJoint)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, D6Joint, PxConstraintConnector)
PX_DEF_BIN_METADATA_ITEM(stream, D6Joint, char, mName, PxMetaDataFlag::ePTR)
PX_DEF_BIN_METADATA_ITEMS_AUTO(stream, D6Joint, PxTransform, mLocalPose, 0)
PX_DEF_BIN_METADATA_ITEM(stream, D6Joint, PxConstraint, mPxConstraint, PxMetaDataFlag::ePTR)
PX_DEF_BIN_METADATA_ITEM(stream, D6Joint, JointData, mData, PxMetaDataFlag::ePTR)
PX_DEF_BIN_METADATA_ITEM(stream, D6Joint, bool, mRecomputeMotion, 0)
PX_DEF_BIN_METADATA_ITEMS_AUTO(stream, D6Joint, bool, mPadding, PxMetaDataFlag::ePADDING)
//------ Extra-data ------
PX_DEF_BIN_METADATA_EXTRA_ITEM(stream, D6Joint, D6JointData, mData, PX_SERIAL_ALIGN)
PX_DEF_BIN_METADATA_EXTRA_NAME(stream, D6Joint, mName, 0)
}
///////////////////////////////////////////////////////////////////////////////
static void getBinaryMetaData_PrismaticJointData(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_TYPEDEF(stream, PxPrismaticJointFlags, PxU16)
PX_DEF_BIN_METADATA_CLASS(stream, PrismaticJointData)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, PrismaticJointData, JointData)
PX_DEF_BIN_METADATA_ITEM(stream, PrismaticJointData, PxJointLinearLimitPair, limit, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PrismaticJointData, PxReal, projectionLinearTolerance, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PrismaticJointData, PxReal, projectionAngularTolerance, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PrismaticJointData, PxPrismaticJointFlags, jointFlags, 0)
#ifdef EXPLICIT_PADDING_METADATA
PX_DEF_BIN_METADATA_ITEM(stream, PrismaticJointData, PxU16, paddingFromFlags, PxMetaDataFlag::ePADDING)
#endif
}
void PrismaticJoint::getBinaryMetaData(PxOutputStream& stream)
{
getBinaryMetaData_PrismaticJointData(stream);
PX_DEF_BIN_METADATA_VCLASS(stream, PrismaticJoint)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, PrismaticJoint, PxJoint)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, PrismaticJoint, PxConstraintConnector)
PX_DEF_BIN_METADATA_ITEM(stream, PrismaticJoint, char, mName, PxMetaDataFlag::ePTR)
PX_DEF_BIN_METADATA_ITEMS_AUTO(stream, PrismaticJoint, PxTransform, mLocalPose, 0)
PX_DEF_BIN_METADATA_ITEM(stream, PrismaticJoint, PxConstraint, mPxConstraint, PxMetaDataFlag::ePTR)
PX_DEF_BIN_METADATA_ITEM(stream, PrismaticJoint, JointData, mData, PxMetaDataFlag::ePTR)
//------ Extra-data ------
PX_DEF_BIN_METADATA_EXTRA_ITEM(stream, PrismaticJoint, PrismaticJointData, mData, PX_SERIAL_ALIGN)
PX_DEF_BIN_METADATA_EXTRA_NAME(stream, PrismaticJoint, mName, 0)
}
///////////////////////////////////////////////////////////////////////////////
static void getBinaryMetaData_FixedJointData(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_CLASS(stream, FixedJointData)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, FixedJointData, JointData)
PX_DEF_BIN_METADATA_ITEM(stream, FixedJointData, PxReal, projectionLinearTolerance, 0)
PX_DEF_BIN_METADATA_ITEM(stream, FixedJointData, PxReal, projectionAngularTolerance, 0)
}
void FixedJoint::getBinaryMetaData(PxOutputStream& stream)
{
getBinaryMetaData_FixedJointData(stream);
PX_DEF_BIN_METADATA_VCLASS(stream, FixedJoint)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, FixedJoint, PxJoint)
PX_DEF_BIN_METADATA_BASE_CLASS(stream, FixedJoint, PxConstraintConnector)
PX_DEF_BIN_METADATA_ITEM(stream, FixedJoint, char, mName, PxMetaDataFlag::ePTR)
PX_DEF_BIN_METADATA_ITEMS_AUTO(stream, FixedJoint, PxTransform, mLocalPose, 0)
PX_DEF_BIN_METADATA_ITEM(stream, FixedJoint, PxConstraint, mPxConstraint, PxMetaDataFlag::ePTR)
PX_DEF_BIN_METADATA_ITEM(stream, FixedJoint, JointData, mData, PxMetaDataFlag::ePTR)
//------ Extra-data ------
PX_DEF_BIN_METADATA_EXTRA_ITEM(stream, FixedJoint, FixedJointData, mData, PX_SERIAL_ALIGN)
PX_DEF_BIN_METADATA_EXTRA_NAME(stream, FixedJoint, mName, 0)
}
void getBinaryMetaData_SerializationContext(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_TYPEDEF(stream, PxSerialObjectId, PxU64)
PX_DEF_BIN_METADATA_TYPEDEF(stream, SerialObjectIndex, PxU32)
PX_DEF_BIN_METADATA_CLASS(stream, Sn::ManifestEntry)
PX_DEF_BIN_METADATA_ITEM(stream, Sn::ManifestEntry, PxU32, offset, 0)
PX_DEF_BIN_METADATA_ITEM(stream, Sn::ManifestEntry, PxType, type, 0)
PX_DEF_BIN_METADATA_CLASS(stream, Sn::ImportReference)
PX_DEF_BIN_METADATA_ITEM(stream, Sn::ImportReference, PxSerialObjectId, id, 0)
PX_DEF_BIN_METADATA_ITEM(stream, Sn::ImportReference, PxType, type, 0)
PX_DEF_BIN_METADATA_CLASS(stream, Sn::ExportReference)
PX_DEF_BIN_METADATA_ITEM(stream, Sn::ExportReference, PxSerialObjectId, id, 0)
PX_DEF_BIN_METADATA_ITEM(stream, Sn::ExportReference, SerialObjectIndex, objIndex, 0)
PX_DEF_BIN_METADATA_CLASS(stream, Sn::InternalReferencePtr)
PX_DEF_BIN_METADATA_ITEM(stream, Sn::InternalReferencePtr, void, reference, PxMetaDataFlag::ePTR)
PX_DEF_BIN_METADATA_ITEM(stream, Sn::InternalReferencePtr, SerialObjectIndex, objIndex, 0)
PX_DEF_BIN_METADATA_CLASS(stream, Sn::InternalReferenceHandle16)
PX_DEF_BIN_METADATA_ITEM(stream, Sn::InternalReferenceHandle16, PxU16, reference, PxMetaDataFlag::eHANDLE)
PX_DEF_BIN_METADATA_ITEM(stream, Sn::InternalReferenceHandle16, PxU16, pad, PxMetaDataFlag::ePADDING)
PX_DEF_BIN_METADATA_ITEM(stream, Sn::InternalReferenceHandle16, SerialObjectIndex, objIndex, 0)
}
namespace physx
{
namespace Ext
{
void GetExtensionsBinaryMetaData(PxOutputStream& stream)
{
PX_DEF_BIN_METADATA_VCLASS(stream,PxConstraintConnector)
getBinaryMetaData_JointData(stream);
getBinaryMetaData_PxD6JointDrive(stream);
getBinaryMetaData_PxJointLimitParameters(stream);
getBinaryMetaData_PxJointLimitCone(stream);
getBinaryMetaData_PxJointLimitPyramid(stream);
getBinaryMetaData_PxJointLinearLimit(stream);
getBinaryMetaData_PxJointLinearLimitPair(stream);
getBinaryMetaData_PxJointAngularLimitPair(stream);
PxJoint::getBinaryMetaData(stream);
RevoluteJoint::getBinaryMetaData(stream);
SphericalJoint::getBinaryMetaData(stream);
DistanceJoint::getBinaryMetaData(stream);
D6Joint::getBinaryMetaData(stream);
PrismaticJoint::getBinaryMetaData(stream);
FixedJoint::getBinaryMetaData(stream);
getBinaryMetaData_SerializationContext(stream);
}
}
}
///////////////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,39 @@
//
// 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-2021 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 PLATFORM_H
#define PLATFORM_H
#include <assert.h>
#include "foundation/Px.h"
#include "PsThread.h"
#include "CmPhysXCommon.h"
#endif

View File

@ -0,0 +1,233 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "ExtPrismaticJoint.h"
#include "ExtConstraintHelper.h"
#include "PxPhysics.h"
using namespace physx;
using namespace Ext;
PxPrismaticJoint* physx::PxPrismaticJointCreate(PxPhysics& physics, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1)
{
PX_CHECK_AND_RETURN_NULL(localFrame0.isSane(), "PxPrismaticJointCreate: local frame 0 is not a valid transform");
PX_CHECK_AND_RETURN_NULL(localFrame1.isSane(), "PxPrismaticJointCreate: local frame 1 is not a valid transform");
PX_CHECK_AND_RETURN_NULL((actor0 && actor0->is<PxRigidBody>()) || (actor1 && actor1->is<PxRigidBody>()), "PxPrismaticJointCreate: at least one actor must be dynamic");
PX_CHECK_AND_RETURN_NULL(actor0 != actor1, "PxPrismaticJointCreate: actors must be different");
PrismaticJoint* j;
PX_NEW_SERIALIZED(j, PrismaticJoint)(physics.getTolerancesScale(), actor0, localFrame0, actor1, localFrame1);
if(j->attach(physics, actor0, actor1))
return j;
PX_DELETE(j);
return NULL;
}
void PrismaticJoint::setProjectionAngularTolerance(PxReal tolerance)
{
PX_CHECK_AND_RETURN(PxIsFinite(tolerance) && tolerance >=0 && tolerance <= PxPi, "PxPrismaticJoint::setProjectionAngularTolerance: invalid parameter");
data().projectionAngularTolerance = tolerance;
markDirty();
}
PxReal PrismaticJoint::getProjectionAngularTolerance() const
{
return data().projectionAngularTolerance;
}
void PrismaticJoint::setProjectionLinearTolerance(PxReal tolerance)
{
PX_CHECK_AND_RETURN(PxIsFinite(tolerance) && tolerance >=0, "PxPrismaticJoint::setProjectionLinearTolerance: invalid parameter");
data().projectionLinearTolerance = tolerance;
markDirty();
}
PxReal PrismaticJoint::getProjectionLinearTolerance() const
{
return data().projectionLinearTolerance;
}
PxPrismaticJointFlags PrismaticJoint::getPrismaticJointFlags(void) const
{
return data().jointFlags;
}
void PrismaticJoint::setPrismaticJointFlags(PxPrismaticJointFlags flags)
{
data().jointFlags = flags; markDirty();
}
void PrismaticJoint::setPrismaticJointFlag(PxPrismaticJointFlag::Enum flag, bool value)
{
if(value)
data().jointFlags |= flag;
else
data().jointFlags &= ~flag;
markDirty();
}
PxJointLinearLimitPair PrismaticJoint::getLimit() const
{
return data().limit;
}
void PrismaticJoint::setLimit(const PxJointLinearLimitPair& limit)
{
PX_CHECK_AND_RETURN(limit.isValid(), "PxPrismaticJoint::setLimit: invalid parameter");
data().limit = limit;
markDirty();
}
bool PrismaticJoint::attach(PxPhysics &physics, PxRigidActor* actor0, PxRigidActor* actor1)
{
mPxConstraint = physics.createConstraint(actor0, actor1, *this, sShaders, sizeof(PrismaticJointData));
return mPxConstraint!=NULL;
}
void PrismaticJoint::exportExtraData(PxSerializationContext& stream)
{
if(mData)
{
stream.alignData(PX_SERIAL_ALIGN);
stream.writeData(mData, sizeof(PrismaticJointData));
}
stream.writeName(mName);
}
void PrismaticJoint::importExtraData(PxDeserializationContext& context)
{
if(mData)
mData = context.readExtraData<PrismaticJointData, PX_SERIAL_ALIGN>();
context.readName(mName);
}
void PrismaticJoint::resolveReferences(PxDeserializationContext& context)
{
setPxConstraint(resolveConstraintPtr(context, getPxConstraint(), getConnector(), sShaders));
}
PrismaticJoint* PrismaticJoint::createObject(PxU8*& address, PxDeserializationContext& context)
{
PrismaticJoint* obj = new (address) PrismaticJoint(PxBaseFlag::eIS_RELEASABLE);
address += sizeof(PrismaticJoint);
obj->importExtraData(context);
obj->resolveReferences(context);
return obj;
}
// global function to share the joint shaders with API capture
const PxConstraintShaderTable* Ext::GetPrismaticJointShaderTable()
{
return &PrismaticJoint::getConstraintShaderTable();
}
//~PX_SERIALIZATION
static void PrismaticJointProject(const void* constantBlock, PxTransform& bodyAToWorld, PxTransform& bodyBToWorld, bool projectToA)
{
const PrismaticJointData& data = *reinterpret_cast<const PrismaticJointData*>(constantBlock);
PxTransform cA2w, cB2w, cB2cA, projected;
joint::computeDerived(data, bodyAToWorld, bodyBToWorld, cA2w, cB2w, cB2cA);
const PxVec3 v(0.0f, cB2cA.p.y, cB2cA.p.z);
bool linearTrunc, angularTrunc;
projected.p = joint::truncateLinear(v, data.projectionLinearTolerance, linearTrunc);
projected.q = joint::truncateAngular(cB2cA.q, PxSin(data.projectionAngularTolerance/2), PxCos(data.projectionAngularTolerance/2), angularTrunc);
if(linearTrunc || angularTrunc)
{
projected.p.x = cB2cA.p.x;
joint::projectTransforms(bodyAToWorld, bodyBToWorld, cA2w, cB2w, projected, data, projectToA);
}
}
static void PrismaticJointVisualize(PxConstraintVisualizer& viz, const void* constantBlock, const PxTransform& body0Transform, const PxTransform& body1Transform, PxU32 flags)
{
const PrismaticJointData& data = *reinterpret_cast<const PrismaticJointData*>(constantBlock);
PxTransform cA2w, cB2w;
joint::computeJointFrames(cA2w, cB2w, data, body0Transform, body1Transform);
if(flags & PxConstraintVisualizationFlag::eLOCAL_FRAMES)
viz.visualizeJointFrames(cA2w, cB2w);
if((flags & PxConstraintVisualizationFlag::eLIMITS) && (data.jointFlags & PxPrismaticJointFlag::eLIMIT_ENABLED))
{
const PxVec3 bOriginInA = cA2w.transformInv(cB2w.p);
const PxReal ordinate = bOriginInA.x;
const PxReal pad = data.limit.isSoft() ? 0.0f : data.limit.contactDistance;
viz.visualizeLinearLimit(cA2w, cB2w, data.limit.lower, ordinate < data.limit.lower + pad);
viz.visualizeLinearLimit(cA2w, cB2w, data.limit.upper, ordinate > data.limit.upper - pad);
}
}
static PxU32 PrismaticJointSolverPrep(Px1DConstraint* constraints,
PxVec3& body0WorldOffset,
PxU32 /*maxConstraints*/,
PxConstraintInvMassScale& invMassScale,
const void* constantBlock,
const PxTransform& bA2w,
const PxTransform& bB2w,
bool /*useExtendedLimits*/,
PxVec3& cA2wOut, PxVec3& cB2wOut)
{
const PrismaticJointData& data = *reinterpret_cast<const PrismaticJointData*>(constantBlock);
PxTransform cA2w, cB2w;
joint::ConstraintHelper ch(constraints, invMassScale, cA2w, cB2w, body0WorldOffset, data, bA2w, bB2w);
if (cA2w.q.dot(cB2w.q)<0.0f) // minimum dist quat (equiv to flipping cB2bB.q, which we don't use anywhere)
cB2w.q = -cB2w.q;
const bool limitEnabled = data.jointFlags & PxPrismaticJointFlag::eLIMIT_ENABLED;
const PxJointLinearLimitPair& limit = data.limit;
const bool limitIsLocked = limitEnabled && limit.lower >= limit.upper;
const PxVec3 bOriginInA = cA2w.transformInv(cB2w.p);
PxVec3 ra, rb;
ch.prepareLockedAxes(cA2w.q, cB2w.q, bOriginInA, limitIsLocked ? 7ul : 6ul, 7ul, ra, rb);
cA2wOut = ra + bA2w.p;
cB2wOut = rb + bB2w.p;
if(limitEnabled && !limitIsLocked)
{
const PxVec3 axis = cA2w.rotate(PxVec3(1.0f, 0.0f, 0.0f)); // PT: TODO: this has already been computed as part of the quat-to-matrix transform within prepareLockedAxes
const PxReal ordinate = bOriginInA.x;
ch.linearLimit(axis, ordinate, limit.upper, limit);
ch.linearLimit(-axis, -ordinate, -limit.lower, limit);
}
return ch.getCount();
}
PxConstraintShaderTable Ext::PrismaticJoint::sShaders = { PrismaticJointSolverPrep, PrismaticJointProject, PrismaticJointVisualize, PxConstraintFlag::Enum(0) };

View File

@ -0,0 +1,133 @@
//
// 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-2021 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 NP_PRISMATICJOINTCONSTRAINT_H
#define NP_PRISMATICJOINTCONSTRAINT_H
#include "common/PxTolerancesScale.h"
#include "extensions/PxPrismaticJoint.h"
#include "ExtJoint.h"
#include "CmUtils.h"
namespace physx
{
struct PxPrismaticJointGeneratedValues;
namespace Ext
{
struct PrismaticJointData : public JointData
{
//= 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.
//==================================================================================================
PxJointLinearLimitPair limit;
PxReal projectionLinearTolerance;
PxReal projectionAngularTolerance;
PxPrismaticJointFlags jointFlags;
// forestall compiler complaints about not being able to generate a constructor
private:
PrismaticJointData(const PxJointLinearLimitPair &pair):
limit(pair) {}
};
typedef Joint<PxPrismaticJoint, PxPrismaticJointGeneratedValues> PrismaticJointT;
class PrismaticJoint : public PrismaticJointT
{
//= 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:
// PX_SERIALIZATION
PrismaticJoint(PxBaseFlags baseFlags) : PrismaticJointT(baseFlags) {}
virtual void exportExtraData(PxSerializationContext& context);
void importExtraData(PxDeserializationContext& context);
void resolveReferences(PxDeserializationContext& context);
static PrismaticJoint* createObject(PxU8*& address, PxDeserializationContext& context);
static void getBinaryMetaData(PxOutputStream& stream);
//~PX_SERIALIZATION
PrismaticJoint(const PxTolerancesScale& scale, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1) :
PrismaticJointT(PxJointConcreteType::ePRISMATIC, PxBaseFlag::eOWNS_MEMORY | PxBaseFlag::eIS_RELEASABLE, actor0, localFrame0, actor1, localFrame1, sizeof(PrismaticJointData), "PrismaticJointData")
{
PrismaticJointData* data = static_cast<PrismaticJointData*>(mData);
data->limit = PxJointLinearLimitPair(scale);
data->projectionLinearTolerance = 1e10f;
data->projectionAngularTolerance = PxPi;
data->jointFlags = PxPrismaticJointFlags();
}
// PxPrismaticJoint
virtual PxReal getPosition() const { return getRelativeTransform().p.x; }
virtual PxReal getVelocity() const { return getRelativeLinearVelocity().x; }
virtual void setLimit(const PxJointLinearLimitPair& limit);
virtual PxJointLinearLimitPair getLimit() const;
virtual void setPrismaticJointFlags(PxPrismaticJointFlags flags);
virtual void setPrismaticJointFlag(PxPrismaticJointFlag::Enum flag, bool value);
virtual PxPrismaticJointFlags getPrismaticJointFlags() const;
virtual void setProjectionLinearTolerance(PxReal tolerance);
virtual PxReal getProjectionLinearTolerance() const;
virtual void setProjectionAngularTolerance(PxReal tolerance);
virtual PxReal getProjectionAngularTolerance() const;
//~PxPrismaticJoint
bool attach(PxPhysics &physics, PxRigidActor* actor0, PxRigidActor* actor1);
static const PxConstraintShaderTable& getConstraintShaderTable() { return sShaders; }
virtual PxConstraintSolverPrep getPrep() const { return sShaders.solverPrep; }
private:
PX_FORCE_INLINE PrismaticJointData& data() const
{
return *static_cast<PrismaticJointData*>(mData);
}
static PxConstraintShaderTable sShaders;
};
} // namespace Ext
namespace Ext
{
// global function to share the joint shaders with API capture
extern "C" const PxConstraintShaderTable* GetPrismaticJointShaderTable();
}
}
#endif

View File

@ -0,0 +1,165 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
// suppress LNK4221
#include "foundation/PxPreprocessor.h"
PX_DUMMY_SYMBOL
#if PX_SUPPORT_PVD
#include "ExtPvd.h"
#include "PxExtensionMetaDataObjects.h"
#include "ExtD6Joint.h"
#include "ExtFixedJoint.h"
#include "ExtSphericalJoint.h"
#include "ExtDistanceJoint.h"
#include "ExtSphericalJoint.h"
#include "ExtRevoluteJoint.h"
#include "ExtPrismaticJoint.h"
#include "ExtJointMetaDataExtensions.h"
#include "PvdMetaDataPropertyVisitor.h"
#include "PvdMetaDataDefineProperties.h"
namespace physx
{
namespace Ext
{
using namespace physx::Vd;
template<typename TObjType, typename TOperator>
inline void visitPvdInstanceProperties( TOperator inOperator )
{
PxClassInfoTraits<TObjType>().Info.visitInstanceProperties( makePvdPropertyFilter( inOperator ), 0 );
}
template<typename TObjType, typename TOperator>
inline void visitPvdProperties( TOperator inOperator )
{
PvdPropertyFilter<TOperator> theFilter( makePvdPropertyFilter( inOperator ) );
PxU32 thePropCount = PxClassInfoTraits<TObjType>().Info.visitBaseProperties( theFilter );
PxClassInfoTraits<TObjType>().Info.visitInstanceProperties( theFilter, thePropCount );
}
Pvd::PvdNameSpace::PvdNameSpace(physx::pvdsdk::PvdDataStream& conn, const char* /*name*/)
: mConnection(conn)
{
}
Pvd::PvdNameSpace::~PvdNameSpace()
{
}
void Pvd::releasePvdInstance(physx::pvdsdk::PvdDataStream& pvdConnection, const PxConstraint& c, const PxJoint& joint)
{
if(!pvdConnection.isConnected())
return;
//remove from scene and from any attached actors.
PxRigidActor* actor0, *actor1;
c.getActors( actor0, actor1 );
PxScene* scene = c.getScene();
if(scene) pvdConnection.removeObjectRef( scene, "Joints", &joint );
if ( actor0 && actor0->getScene() ) pvdConnection.removeObjectRef( actor0, "Joints", &joint );
if ( actor1 && actor1->getScene()) pvdConnection.removeObjectRef( actor1, "Joints", &joint );
pvdConnection.destroyInstance(&joint);
}
template<typename TObjType>
void registerProperties( PvdDataStream& inStream )
{
inStream.createClass<TObjType>();
PvdPropertyDefinitionHelper& theHelper( inStream.getPropertyDefinitionHelper() );
PvdClassInfoDefine theDefinitionObj( theHelper, getPvdNamespacedNameForType<TObjType>() );
visitPvdInstanceProperties<TObjType>( theDefinitionObj );
}
template<typename TObjType, typename TValueStructType>
void registerPropertiesAndValueStruct( PvdDataStream& inStream )
{
inStream.createClass<TObjType>();
inStream.deriveClass<PxJoint,TObjType>();
PvdPropertyDefinitionHelper& theHelper( inStream.getPropertyDefinitionHelper() );
{
PvdClassInfoDefine theDefinitionObj( theHelper, getPvdNamespacedNameForType<TObjType>() );
visitPvdInstanceProperties<TObjType>( theDefinitionObj );
}
{
PvdClassInfoValueStructDefine theDefinitionObj( theHelper );
visitPvdProperties<TObjType>( theDefinitionObj );
theHelper.addPropertyMessage<TObjType,TValueStructType>();
}
}
void Pvd::sendClassDescriptions(physx::pvdsdk::PvdDataStream& inStream)
{
if (inStream.isClassExist<PxJoint>())
return;
{ //PxJoint
registerProperties<PxJoint>( inStream );
inStream.createProperty<PxJoint,ObjectRef>( "Parent", "parents" );
registerPropertiesAndValueStruct<PxDistanceJoint,PxDistanceJointGeneratedValues>( inStream);
registerPropertiesAndValueStruct<PxContactJoint, PxContactJointGeneratedValues>(inStream);
registerPropertiesAndValueStruct<PxFixedJoint,PxFixedJointGeneratedValues>( inStream);
registerPropertiesAndValueStruct<PxPrismaticJoint,PxPrismaticJointGeneratedValues>( inStream);
registerPropertiesAndValueStruct<PxSphericalJoint,PxSphericalJointGeneratedValues>( inStream);
registerPropertiesAndValueStruct<PxRevoluteJoint,PxRevoluteJointGeneratedValues>( inStream);
registerPropertiesAndValueStruct<PxD6Joint,PxD6JointGeneratedValues>( inStream);
}
}
void Pvd::setActors( physx::pvdsdk::PvdDataStream& inStream, const PxJoint& inJoint, const PxConstraint& c, const PxActor* newActor0, const PxActor* newActor1 )
{
PxRigidActor* actor0, *actor1;
c.getActors( actor0, actor1 );
if ( actor0 )
inStream.removeObjectRef( actor0, "Joints", &inJoint );
if ( actor1 )
inStream.removeObjectRef( actor1, "Joints", &inJoint );
if ( newActor0 && newActor0->getScene())
inStream.pushBackObjectRef( newActor0, "Joints", &inJoint );
if ( newActor1 && newActor1->getScene())
inStream.pushBackObjectRef( newActor1, "Joints", &inJoint );
inStream.setPropertyValue( &inJoint, "Actors.actor0", reinterpret_cast<const void*>(newActor0) );
inStream.setPropertyValue( &inJoint, "Actors.actor1", reinterpret_cast<const void*>(newActor1) );
const void* parent = newActor0 ? newActor0 : newActor1;
inStream.setPropertyValue( &inJoint, "Parent", parent );
if((newActor0 && !newActor0->getScene()) || (newActor1 && !newActor1->getScene()))
{
inStream.removeObjectRef( c.getScene(), "Joints", &inJoint );
}
}
}
}
#endif // PX_SUPPORT_PVD

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-2021 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 EXT_PVD_H
#define EXT_PVD_H
#if PX_SUPPORT_PVD
#include "extensions/PxJoint.h"
#include "CmPhysXCommon.h"
#include "PsUserAllocated.h"
#include "PxPvdDataStream.h"
#include "PvdTypeNames.h"
#include "PxExtensionMetaDataObjects.h"
#include "PxPvdObjectModelBaseTypes.h"
namespace physx
{
class PxJoint;
class PxD6Joint;
class PxDistanceJoint;
class PxFixedJoint;
class PxPrismaticJoint;
class PxRevoluteJoint;
class PxSphericalJoint;
class PxContactJoint;
}
#define JOINT_GROUP 3
namespace physx
{
namespace pvdsdk {
#define DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP( type ) DEFINE_PVD_TYPE_NAME_MAP( physx::type, "physx3", #type )
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxJoint)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxJointGeneratedValues)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxFixedJoint)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxFixedJointGeneratedValues)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxDistanceJoint)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxDistanceJointGeneratedValues)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxContactJoint)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxContactJointGeneratedValues)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxPrismaticJoint)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxPrismaticJointGeneratedValues)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxRevoluteJoint)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxRevoluteJointGeneratedValues)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxSphericalJoint)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxSphericalJointGeneratedValues)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxD6Joint)
DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP(PxD6JointGeneratedValues)
#undef DEFINE_NATIVE_PVD_PHYSX3_TYPE_MAP
} //pvdsdk
} // physx
namespace physx
{
namespace Ext
{
using namespace physx::pvdsdk;
class Pvd: public physx::shdfnd::UserAllocated
{
Pvd& operator=(const Pvd&);
public:
class PvdNameSpace
{
public:
PvdNameSpace(PvdDataStream& conn, const char* name);
~PvdNameSpace();
private:
PvdNameSpace& operator=(const PvdNameSpace&);
PvdDataStream& mConnection;
};
static void setActors( PvdDataStream& PvdDataStream,
const PxJoint& inJoint, const PxConstraint& c, const PxActor* newActor0, const PxActor* newActor1 );
template<typename TObjType>
static void createInstance( PvdDataStream& inStream, const PxConstraint& c, const TObjType& inSource )
{
inStream.createInstance( &inSource );
inStream.pushBackObjectRef( c.getScene(), "Joints", &inSource );
class ConstraintUpdateCmd : public PvdDataStream::PvdCommand
{
ConstraintUpdateCmd &operator=(const ConstraintUpdateCmd&) { PX_ASSERT(0); return *this; } //PX_NOCOPY doesn't work for local classes
public:
const PxConstraint& mConstraint;
const PxJoint& mJoint;
PxRigidActor* actor0, *actor1;
ConstraintUpdateCmd(const PxConstraint& constraint, const PxJoint& joint):PvdDataStream::PvdCommand(), mConstraint(constraint), mJoint(joint)
{
mConstraint.getActors( actor0, actor1 );
}
//Assigned is needed for copying
ConstraintUpdateCmd(const ConstraintUpdateCmd& cmd)
:PvdDataStream::PvdCommand(), mConstraint(cmd.mConstraint), mJoint(cmd.mJoint)
{
}
virtual bool canRun(PvdInstanceDataStream &inStream_ )
{
PX_ASSERT(inStream_.isInstanceValid(&mJoint));
//When run this command, the constraint maybe buffer removed
return ((actor0 == NULL) || inStream_.isInstanceValid(actor0))
&& ((actor1 == NULL) || inStream_.isInstanceValid(actor1));
}
virtual void run( PvdInstanceDataStream &inStream_ )
{
//When run this command, the constraint maybe buffer removed
if(!inStream_.isInstanceValid(&mJoint))
return;
PxRigidActor* actor0_, *actor1_;
mConstraint.getActors( actor0_, actor1_ );
if ( actor0_ && (inStream_.isInstanceValid(actor0_)) )
inStream_.pushBackObjectRef( actor0_, "Joints", &mJoint );
if ( actor1_ && (inStream_.isInstanceValid(actor1_)) )
inStream_.pushBackObjectRef( actor1_, "Joints", &mJoint );
const void* parent = actor0_ ? actor0_ : actor1_;
inStream_.setPropertyValue( &mJoint, "Parent", parent );
}
};
ConstraintUpdateCmd* cmd = PX_PLACEMENT_NEW(inStream.allocateMemForCmd(sizeof(ConstraintUpdateCmd)),
ConstraintUpdateCmd)(c, inSource);
if(cmd->canRun( inStream ))
cmd->run( inStream );
else
inStream.pushPvdCommand( *cmd );
}
template<typename jointtype, typename structValue>
static void updatePvdProperties(PvdDataStream& pvdConnection, const jointtype& joint)
{
structValue theValueStruct( &joint );
pvdConnection.setPropertyMessage( &joint, theValueStruct );
}
template<typename jointtype>
static void simUpdate(PvdDataStream& /*pvdConnection*/, const jointtype& /*joint*/) {}
template<typename jointtype>
static void createPvdInstance(PvdDataStream& pvdConnection, const PxConstraint& c, const jointtype& joint)
{
createInstance<jointtype>( pvdConnection, c, joint );
}
static void releasePvdInstance(PvdDataStream& pvdConnection, const PxConstraint& c, const PxJoint& joint);
static void sendClassDescriptions(PvdDataStream& pvdConnection);
};
} // ext
} // physx
#endif // PX_SUPPORT_PVD
#endif // EXT_PVD_H

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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "foundation/PxAllocatorCallback.h"
#include "extensions/PxStringTableExt.h"
#include "PxProfileAllocatorWrapper.h" //tools for using a custom allocator
#include "PsString.h"
#include "PsUserAllocated.h"
#include "CmPhysXCommon.h"
namespace physx
{
using namespace physx::profile;
class PxStringTableImpl : public PxStringTable, public Ps::UserAllocated
{
typedef PxProfileHashMap<const char*, PxU32> THashMapType;
PxProfileAllocatorWrapper mWrapper;
THashMapType mHashMap;
public:
PxStringTableImpl( PxAllocatorCallback& inAllocator )
: mWrapper ( inAllocator )
, mHashMap ( mWrapper )
{
}
virtual ~PxStringTableImpl()
{
for ( THashMapType::Iterator iter = mHashMap.getIterator();
iter.done() == false;
++iter )
PX_PROFILE_DELETE( mWrapper, const_cast<char*>( iter->first ) );
mHashMap.clear();
}
virtual const char* allocateStr( const char* inSrc )
{
if ( inSrc == NULL )
inSrc = "";
const THashMapType::Entry* existing( mHashMap.find( inSrc ) );
if ( existing == NULL )
{
size_t len( strlen( inSrc ) );
len += 1;
char* newMem = reinterpret_cast<char*>(mWrapper.getAllocator().allocate( len, "PxStringTableImpl: const char*", __FILE__, __LINE__ ));
physx::shdfnd::strlcpy( newMem, len, inSrc );
mHashMap.insert( newMem, 1 );
return newMem;
}
else
{
++const_cast<THashMapType::Entry*>(existing)->second;
return existing->first;
}
}
/**
* Release the string table and all the strings associated with it.
*/
virtual void release()
{
PX_PROFILE_DELETE( mWrapper.getAllocator(), this );
}
};
PxStringTable& PxStringTableExt::createStringTable( PxAllocatorCallback& inAllocator )
{
return *PX_PROFILE_NEW( inAllocator, PxStringTableImpl )( inAllocator );
}
}

View File

@ -0,0 +1,305 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "geometry/PxBoxGeometry.h"
#include "geometry/PxSphereGeometry.h"
#include "geometry/PxCapsuleGeometry.h"
#include "geometry/PxConvexMeshGeometry.h"
#include "geometry/PxConvexMesh.h"
#include "extensions/PxShapeExt.h"
#include "extensions/PxRaycastCCD.h"
#include "PxScene.h"
#include "PxRigidDynamic.h"
#include "PsArray.h"
using namespace physx;
namespace physx
{
class RaycastCCDManagerInternal
{
PX_NOCOPY(RaycastCCDManagerInternal)
public:
RaycastCCDManagerInternal(PxScene* scene) : mScene(scene) {}
~RaycastCCDManagerInternal(){}
bool registerRaycastCCDObject(PxRigidDynamic* actor, PxShape* shape);
void doRaycastCCD(bool doDynamicDynamicCCD);
struct CCDObject
{
PX_FORCE_INLINE CCDObject(PxRigidDynamic* actor, PxShape* shape, const PxVec3& witness) : mActor(actor), mShape(shape), mWitness(witness) {}
PxRigidDynamic* mActor;
PxShape* mShape;
PxVec3 mWitness;
};
private:
PxScene* mScene;
physx::shdfnd::Array<CCDObject> mObjects;
};
}
static PxVec3 getShapeCenter(PxShape* shape, const PxTransform& pose)
{
PxVec3 offset(0.0f);
if(shape->getGeometryType()==PxGeometryType::eCONVEXMESH)
{
PxConvexMeshGeometry geometry;
bool status = shape->getConvexMeshGeometry(geometry);
PX_UNUSED(status);
PX_ASSERT(status);
PxReal mass;
PxMat33 localInertia;
PxVec3 localCenterOfMass;
geometry.convexMesh->getMassInformation(mass, localInertia, localCenterOfMass);
offset += localCenterOfMass;
}
return pose.transform(offset);
}
static PX_FORCE_INLINE PxVec3 getShapeCenter(PxRigidActor* actor, PxShape* shape)
{
const PxTransform pose = PxShapeExt::getGlobalPose(*shape, *actor);
return getShapeCenter(shape, pose);
}
static PxReal computeInternalRadius(PxRigidActor* actor, PxShape* shape, const PxVec3& dir)
{
const PxBounds3 bounds = PxShapeExt::getWorldBounds(*shape, *actor);
const PxReal diagonal = (bounds.maximum - bounds.minimum).magnitude();
const PxReal offsetFromOrigin = diagonal * 2.0f;
PxTransform pose = PxShapeExt::getGlobalPose(*shape, *actor);
PxReal internalRadius = 0.0f;
const PxReal length = offsetFromOrigin*2.0f;
switch(shape->getGeometryType())
{
case PxGeometryType::eSPHERE:
{
PxSphereGeometry geometry;
bool status = shape->getSphereGeometry(geometry);
PX_UNUSED(status);
PX_ASSERT(status);
internalRadius = geometry.radius;
}
break;
case PxGeometryType::eBOX:
case PxGeometryType::eCAPSULE:
{
pose.p = PxVec3(0.0f);
const PxVec3 virtualOrigin = pose.p + dir * offsetFromOrigin;
PxRaycastHit hit;
PxU32 nbHits = PxGeometryQuery::raycast(virtualOrigin, -dir, shape->getGeometry().any(), pose, length, PxHitFlags(0), 1, &hit);
PX_UNUSED(nbHits);
PX_ASSERT(nbHits);
internalRadius = offsetFromOrigin - hit.distance;
}
break;
case PxGeometryType::eCONVEXMESH:
{
PxVec3 shapeCenter = getShapeCenter(shape, pose);
shapeCenter -= pose.p;
pose.p = PxVec3(0.0f);
const PxVec3 virtualOrigin = shapeCenter + dir * offsetFromOrigin;
PxRaycastHit hit;
PxU32 nbHits = PxGeometryQuery::raycast(virtualOrigin, -dir, shape->getGeometry().any(), pose, length, PxHitFlags(0), 1, &hit);
PX_UNUSED(nbHits);
PX_ASSERT(nbHits);
internalRadius = offsetFromOrigin - hit.distance;
}
break;
case PxGeometryType::ePLANE:
case PxGeometryType::eHEIGHTFIELD:
case PxGeometryType::eTRIANGLEMESH:
case PxGeometryType::eGEOMETRY_COUNT:
case PxGeometryType::eINVALID:
break;
}
return internalRadius;
}
class CCDRaycastFilterCallback : public PxQueryFilterCallback
{
public:
CCDRaycastFilterCallback(PxRigidActor* actor, PxShape* shape) : mActor(actor), mShape(shape){}
PxRigidActor* mActor;
PxShape* mShape;
virtual PxQueryHitType::Enum preFilter(const PxFilterData&, const PxShape* shape, const PxRigidActor* actor, PxHitFlags&)
{
if(mActor==actor && mShape==shape)
return PxQueryHitType::eNONE;
return PxQueryHitType::eBLOCK;
}
virtual PxQueryHitType::Enum postFilter(const PxFilterData&, const PxQueryHit&)
{
return PxQueryHitType::eNONE;
}
};
static bool CCDRaycast(PxScene* scene, PxRigidActor* actor, PxShape* shape, const PxVec3& origin, const PxVec3& unitDir, const PxReal distance, PxRaycastHit& hit, bool dyna_dyna)
{
const PxQueryFlags qf(dyna_dyna ? PxQueryFlags(PxQueryFlag::eSTATIC|PxQueryFlag::eDYNAMIC|PxQueryFlag::ePREFILTER) : PxQueryFlags(PxQueryFlag::eSTATIC));
const PxQueryFilterData filterData(PxFilterData(), qf);
CCDRaycastFilterCallback CB(actor, shape);
PxRaycastBuffer buf1;
scene->raycast(origin, unitDir, distance, buf1, PxHitFlags(0), filterData, &CB);
hit = buf1.block;
return buf1.hasBlock;
}
static PxRigidDynamic* canDoCCD(PxRigidActor& actor, PxShape* /*shape*/)
{
if(actor.getConcreteType()!=PxConcreteType::eRIGID_DYNAMIC)
return NULL; // PT: no need to do it for statics
PxRigidDynamic* dyna = static_cast<PxRigidDynamic*>(&actor);
const PxU32 nbShapes = dyna->getNbShapes();
if(nbShapes!=1)
return NULL; // PT: only works with simple actors for now
if(dyna->getRigidBodyFlags() & PxRigidBodyFlag::eKINEMATIC)
return NULL; // PT: no need to do it for kinematics
return dyna;
}
static bool doRaycastCCD(PxScene* scene, const RaycastCCDManagerInternal::CCDObject& object, PxTransform& newPose, PxVec3& newShapeCenter, bool dyna_dyna)
{
PxRigidDynamic* dyna = canDoCCD(*object.mActor, object.mShape);
if(!dyna)
return true;
bool updateCCDWitness = true;
const PxVec3 offset = newPose.p - newShapeCenter;
const PxVec3& origin = object.mWitness;
const PxVec3& dest = newShapeCenter;
PxVec3 dir = dest - origin;
const PxReal length = dir.magnitude();
if(length!=0.0f)
{
dir /= length;
const PxReal internalRadius = computeInternalRadius(object.mActor, object.mShape, dir);
PxRaycastHit hit;
if(internalRadius!=0.0f && CCDRaycast(scene, object.mActor, object.mShape, origin, dir, length, hit, dyna_dyna))
{
updateCCDWitness = false;
const PxReal radiusLimit = internalRadius * 0.75f;
if(hit.distance>radiusLimit)
{
newShapeCenter = origin + dir * (hit.distance - radiusLimit);
}
else
{
if(hit.actor->getConcreteType()==PxConcreteType::eRIGID_DYNAMIC)
return true;
newShapeCenter = origin;
}
newPose.p = offset + newShapeCenter;
const PxTransform shapeLocalPose = object.mShape->getLocalPose();
const PxTransform inverseShapeLocalPose = shapeLocalPose.getInverse();
const PxTransform newGlobalPose = newPose * inverseShapeLocalPose;
dyna->setGlobalPose(newGlobalPose);
}
}
return updateCCDWitness;
}
bool RaycastCCDManagerInternal::registerRaycastCCDObject(PxRigidDynamic* actor, PxShape* shape)
{
if(!actor || !shape)
return false;
mObjects.pushBack(CCDObject(actor, shape, getShapeCenter(actor, shape)));
return true;
}
void RaycastCCDManagerInternal::doRaycastCCD(bool doDynamicDynamicCCD)
{
const PxU32 nbObjects = mObjects.size();
for(PxU32 i=0;i<nbObjects;i++)
{
CCDObject& object = mObjects[i];
if(object.mActor->isSleeping())
continue;
PxTransform newPose = PxShapeExt::getGlobalPose(*object.mShape, *object.mActor);
PxVec3 newShapeCenter = getShapeCenter(object.mShape, newPose);
if(::doRaycastCCD(mScene, object, newPose, newShapeCenter, doDynamicDynamicCCD))
object.mWitness = newShapeCenter;
}
}
RaycastCCDManager::RaycastCCDManager(PxScene* scene)
{
mImpl = new RaycastCCDManagerInternal(scene);
}
RaycastCCDManager::~RaycastCCDManager()
{
delete mImpl;
}
bool RaycastCCDManager::registerRaycastCCDObject(PxRigidDynamic* actor, PxShape* shape)
{
return mImpl->registerRaycastCCDObject(actor, shape);
}
void RaycastCCDManager::doRaycastCCD(bool doDynamicDynamicCCD)
{
mImpl->doRaycastCCD(doDynamicDynamicCCD);
}

View File

@ -0,0 +1,339 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "ExtRevoluteJoint.h"
#include "ExtConstraintHelper.h"
#include "PxPhysics.h"
using namespace physx;
using namespace Ext;
PxRevoluteJoint* physx::PxRevoluteJointCreate(PxPhysics& physics, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1)
{
PX_CHECK_AND_RETURN_NULL(localFrame0.isSane(), "PxRevoluteJointCreate: local frame 0 is not a valid transform");
PX_CHECK_AND_RETURN_NULL(localFrame1.isSane(), "PxRevoluteJointCreate: local frame 1 is not a valid transform");
PX_CHECK_AND_RETURN_NULL(actor0 != actor1, "PxRevoluteJointCreate: actors must be different");
PX_CHECK_AND_RETURN_NULL((actor0 && actor0->is<PxRigidBody>()) || (actor1 && actor1->is<PxRigidBody>()), "PxRevoluteJointCreate: at least one actor must be dynamic");
RevoluteJoint* j;
PX_NEW_SERIALIZED(j, RevoluteJoint)(physics.getTolerancesScale(), actor0, localFrame0, actor1, localFrame1);
if(j->attach(physics, actor0, actor1))
return j;
PX_DELETE(j);
return NULL;
}
PxReal RevoluteJoint::getAngle() const
{
return getTwistAngle_Internal();
}
PxReal RevoluteJoint::getVelocity() const
{
return getRelativeAngularVelocity().magnitude();
}
PxJointAngularLimitPair RevoluteJoint::getLimit() const
{
return data().limit;
}
void RevoluteJoint::setLimit(const PxJointAngularLimitPair& limit)
{
PX_CHECK_AND_RETURN(limit.isValid(), "PxRevoluteJoint::setLimit: limit invalid");
PX_CHECK_AND_RETURN(limit.lower>-PxTwoPi && limit.upper<PxTwoPi , "PxRevoluteJoint::twist limit must be strictly between -2*PI and 2*PI");
data().limit = limit;
markDirty();
}
PxReal RevoluteJoint::getDriveVelocity() const
{
return data().driveVelocity;
}
void RevoluteJoint::setDriveVelocity(PxReal velocity, bool autowake)
{
PX_CHECK_AND_RETURN(PxIsFinite(velocity), "PxRevoluteJoint::setDriveVelocity: invalid parameter");
data().driveVelocity = velocity;
if(autowake)
wakeUpActors();
markDirty();
}
PxReal RevoluteJoint::getDriveForceLimit() const
{
return data().driveForceLimit;
}
void RevoluteJoint::setDriveForceLimit(PxReal forceLimit)
{
PX_CHECK_AND_RETURN(PxIsFinite(forceLimit), "PxRevoluteJoint::setDriveForceLimit: invalid parameter");
data().driveForceLimit = forceLimit;
markDirty();
}
PxReal RevoluteJoint::getDriveGearRatio() const
{
return data().driveGearRatio;
}
void RevoluteJoint::setDriveGearRatio(PxReal gearRatio)
{
PX_CHECK_AND_RETURN(PxIsFinite(gearRatio) && gearRatio>0, "PxRevoluteJoint::setDriveGearRatio: invalid parameter");
data().driveGearRatio = gearRatio;
markDirty();
}
void RevoluteJoint::setProjectionAngularTolerance(PxReal tolerance)
{
PX_CHECK_AND_RETURN(PxIsFinite(tolerance) && tolerance>=0 && tolerance<=PxPi, "PxRevoluteJoint::setProjectionAngularTolerance: invalid parameter");
data().projectionAngularTolerance = tolerance;
markDirty();
}
PxReal RevoluteJoint::getProjectionAngularTolerance() const
{
return data().projectionAngularTolerance;
}
void RevoluteJoint::setProjectionLinearTolerance(PxReal tolerance)
{
PX_CHECK_AND_RETURN(PxIsFinite(tolerance) && tolerance >=0, "PxRevoluteJoint::setProjectionLinearTolerance: invalid parameter");
data().projectionLinearTolerance = tolerance;
markDirty();
}
PxReal RevoluteJoint::getProjectionLinearTolerance() const
{
return data().projectionLinearTolerance;
}
PxRevoluteJointFlags RevoluteJoint::getRevoluteJointFlags(void) const
{
return data().jointFlags;
}
void RevoluteJoint::setRevoluteJointFlags(PxRevoluteJointFlags flags)
{
data().jointFlags = flags;
}
void RevoluteJoint::setRevoluteJointFlag(PxRevoluteJointFlag::Enum flag, bool value)
{
if(value)
data().jointFlags |= flag;
else
data().jointFlags &= ~flag;
markDirty();
}
bool RevoluteJoint::attach(PxPhysics &physics, PxRigidActor* actor0, PxRigidActor* actor1)
{
mPxConstraint = physics.createConstraint(actor0, actor1, *this, sShaders, sizeof(RevoluteJointData));
return mPxConstraint!=NULL;
}
void RevoluteJoint::exportExtraData(PxSerializationContext& stream)
{
if(mData)
{
stream.alignData(PX_SERIAL_ALIGN);
stream.writeData(mData, sizeof(RevoluteJointData));
}
stream.writeName(mName);
}
void RevoluteJoint::importExtraData(PxDeserializationContext& context)
{
if(mData)
mData = context.readExtraData<RevoluteJointData, PX_SERIAL_ALIGN>();
context.readName(mName);
}
void RevoluteJoint::resolveReferences(PxDeserializationContext& context)
{
setPxConstraint(resolveConstraintPtr(context, getPxConstraint(), getConnector(), sShaders));
}
RevoluteJoint* RevoluteJoint::createObject(PxU8*& address, PxDeserializationContext& context)
{
RevoluteJoint* obj = new (address) RevoluteJoint(PxBaseFlag::eIS_RELEASABLE);
address += sizeof(RevoluteJoint);
obj->importExtraData(context);
obj->resolveReferences(context);
return obj;
}
// global function to share the joint shaders with API capture
const PxConstraintShaderTable* Ext::GetRevoluteJointShaderTable()
{
return &RevoluteJoint::getConstraintShaderTable();
}
//~PX_SERIALIZATION
static void RevoluteJointProject(const void* constantBlock, PxTransform& bodyAToWorld, PxTransform& bodyBToWorld, bool projectToA)
{
const RevoluteJointData& data = *reinterpret_cast<const RevoluteJointData*>(constantBlock);
PxTransform cA2w, cB2w, cB2cA, projected;
joint::computeDerived(data, bodyAToWorld, bodyBToWorld, cA2w, cB2w, cB2cA, false);
bool linearTrunc, angularTrunc;
projected.p = joint::truncateLinear(cB2cA.p, data.projectionLinearTolerance, linearTrunc);
PxQuat swing, twist, projSwing;
Ps::separateSwingTwist(cB2cA.q, swing, twist);
projSwing = joint::truncateAngular(swing, PxSin(data.projectionAngularTolerance/2), PxCos(data.projectionAngularTolerance/2), angularTrunc);
if(linearTrunc || angularTrunc)
{
projected.q = projSwing * twist;
joint::projectTransforms(bodyAToWorld, bodyBToWorld, cA2w, cB2w, projected, data, projectToA);
}
}
static PxQuat computeTwist(const PxTransform& cA2w, const PxTransform& cB2w)
{
// PT: following code is the same as this part of the "getAngle" function:
// const PxQuat q = getRelativeTransform().q;
// PxQuat swing, twist;
// Ps::separateSwingTwist(q, swing, twist);
// But it's done a little bit more efficiently since we don't need the swing quat.
// PT: rotation part of "const PxTransform cB2cA = cA2w.transformInv(cB2w);"
const PxQuat cB2cAq = cA2w.q.getConjugate() * cB2w.q;
// PT: twist part of "Ps::separateSwingTwist(cB2cAq,swing,twist)" (more or less)
return PxQuat(cB2cAq.x, 0.0f, 0.0f, cB2cAq.w);
}
// PT: this version is similar to the "getAngle" function, but the twist is computed slightly differently.
static PX_FORCE_INLINE PxReal computePhi(const PxTransform& cA2w, const PxTransform& cB2w)
{
PxQuat twist = computeTwist(cA2w, cB2w);
twist.normalize();
PxReal angle = twist.getAngle();
if(twist.x<0.0f)
angle = -angle;
return angle;
}
static void RevoluteJointVisualize(PxConstraintVisualizer& viz, const void* constantBlock, const PxTransform& body0Transform, const PxTransform& body1Transform, PxU32 flags)
{
const RevoluteJointData& data = *reinterpret_cast<const RevoluteJointData*>(constantBlock);
PxTransform cA2w, cB2w;
joint::computeJointFrames(cA2w, cB2w, data, body0Transform, body1Transform);
if(flags & PxConstraintVisualizationFlag::eLOCAL_FRAMES)
viz.visualizeJointFrames(cA2w, cB2w);
if((data.jointFlags & PxRevoluteJointFlag::eLIMIT_ENABLED) && (flags & PxConstraintVisualizationFlag::eLIMITS))
{
const PxReal angle = computePhi(cA2w, cB2w);
const PxReal pad = data.limit.contactDistance;
const PxReal low = data.limit.lower;
const PxReal high = data.limit.upper;
const bool active = isLimitActive(data.limit, pad, angle, low, high);
viz.visualizeAngularLimit(cA2w, data.limit.lower, data.limit.upper, active);
}
}
static PxU32 RevoluteJointSolverPrep(Px1DConstraint* constraints,
PxVec3& body0WorldOffset,
PxU32 /*maxConstraints*/,
PxConstraintInvMassScale& invMassScale,
const void* constantBlock,
const PxTransform& bA2w,
const PxTransform& bB2w,
bool useExtendedLimits,
PxVec3& cA2wOut, PxVec3& cB2wOut)
{
const RevoluteJointData& data = *reinterpret_cast<const RevoluteJointData*>(constantBlock);
PxTransform cA2w, cB2w;
joint::ConstraintHelper ch(constraints, invMassScale, cA2w, cB2w, body0WorldOffset, data, bA2w, bB2w);
const PxJointAngularLimitPair& limit = data.limit;
const bool limitEnabled = data.jointFlags & PxRevoluteJointFlag::eLIMIT_ENABLED;
const bool limitIsLocked = limitEnabled && limit.lower >= limit.upper;
// PT: it is a mistake to use the neighborhood operator since it
// prevents us from using the quat's double-cover feature.
if(!useExtendedLimits && cB2w.q.dot(cA2w.q)<0.0f)
cB2w.q = -cB2w.q;
PxVec3 ra, rb;
ch.prepareLockedAxes(cA2w.q, cB2w.q, cA2w.transformInv(cB2w.p), 7, PxU32(limitIsLocked ? 7 : 6), ra, rb);
cA2wOut = ra + bA2w.p;
cB2wOut = rb + bB2w.p;
if(limitIsLocked)
return ch.getCount();
const PxVec3 axis = cA2w.rotate(PxVec3(1.0f, 0.0f, 0.0f));
if(data.jointFlags & PxRevoluteJointFlag::eDRIVE_ENABLED)
{
Px1DConstraint* c = ch.getConstraintRow();
c->solveHint = PxConstraintSolveHint::eNONE;
c->linear0 = PxVec3(0.0f);
c->angular0 = -axis;
c->linear1 = PxVec3(0.0f);
c->angular1 = -axis * data.driveGearRatio;
c->velocityTarget = data.driveVelocity;
c->minImpulse = -data.driveForceLimit;
c->maxImpulse = data.driveForceLimit;
c->flags |= Px1DConstraintFlag::eANGULAR_CONSTRAINT;
if(data.jointFlags & PxRevoluteJointFlag::eDRIVE_FREESPIN)
{
if(data.driveVelocity > 0.0f)
c->minImpulse = 0.0f;
if(data.driveVelocity < 0.0f)
c->maxImpulse = 0.0f;
}
c->flags |= Px1DConstraintFlag::eHAS_DRIVE_LIMIT;
}
if(limitEnabled)
{
const PxReal phi = computePhi(cA2w, cB2w);
ch.anglePair(phi, data.limit.lower, data.limit.upper, data.limit.contactDistance, axis, limit);
}
return ch.getCount();
}
PxConstraintShaderTable Ext::RevoluteJoint::sShaders = { RevoluteJointSolverPrep, RevoluteJointProject, RevoluteJointVisualize, PxConstraintFlag::Enum(0) };

View File

@ -0,0 +1,154 @@
//
// 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-2021 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 NP_REVOLUTEJOINTCONSTRAINT_H
#define NP_REVOLUTEJOINTCONSTRAINT_H
#include "extensions/PxRevoluteJoint.h"
#include "ExtJoint.h"
#include "PsIntrinsics.h"
#include "CmUtils.h"
namespace physx
{
class PxConstraintSolverPrepKernel;
class PxConstraintProjectionKernel;
struct PxRevoluteJointGeneratedValues;
namespace Ext
{
struct RevoluteJointData : public JointData
{
//= 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 driveVelocity;
PxReal driveForceLimit;
PxReal driveGearRatio;
PxJointAngularLimitPair limit;
PxReal projectionLinearTolerance;
PxReal projectionAngularTolerance;
PxRevoluteJointFlags jointFlags;
// forestall compiler complaints about not being able to generate a constructor
private:
RevoluteJointData(const PxJointAngularLimitPair &pair):
limit(pair) {}
};
typedef Joint<PxRevoluteJoint, PxRevoluteJointGeneratedValues> RevoluteJointT;
class RevoluteJoint : public RevoluteJointT
{
//= 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:
// PX_SERIALIZATION
RevoluteJoint(PxBaseFlags baseFlags) : RevoluteJointT(baseFlags) {}
void resolveReferences(PxDeserializationContext& context);
virtual void exportExtraData(PxSerializationContext& context);
void importExtraData(PxDeserializationContext& context);
static RevoluteJoint* createObject(PxU8*& address, PxDeserializationContext& context);
static void getBinaryMetaData(PxOutputStream& stream);
//~PX_SERIALIZATION
RevoluteJoint(const PxTolerancesScale& /*scale*/, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1) :
RevoluteJointT(PxJointConcreteType::eREVOLUTE, PxBaseFlag::eOWNS_MEMORY | PxBaseFlag::eIS_RELEASABLE, actor0, localFrame0, actor1, localFrame1, sizeof(RevoluteJointData), "RevoluteJointData")
{
RevoluteJointData* data = static_cast<RevoluteJointData*>(mData);
data->projectionLinearTolerance = 1e10f;
data->projectionAngularTolerance = PxPi;
data->driveForceLimit = PX_MAX_F32;
data->driveVelocity = 0.0f;
data->driveGearRatio = 1.0f;
data->limit = PxJointAngularLimitPair(-PxPi/2, PxPi/2);
data->jointFlags = PxRevoluteJointFlags();
}
// PxRevoluteJoint
virtual PxReal getAngle() const;
virtual PxReal getVelocity() const;
virtual void setLimit(const PxJointAngularLimitPair& limit);
virtual PxJointAngularLimitPair getLimit() const;
virtual void setDriveVelocity(PxReal velocity, bool autowake = true);
virtual PxReal getDriveVelocity() const;
virtual void setDriveForceLimit(PxReal forceLimit);
virtual PxReal getDriveForceLimit() const;
virtual void setDriveGearRatio(PxReal gearRatio);
virtual PxReal getDriveGearRatio() const;
virtual void setRevoluteJointFlags(PxRevoluteJointFlags flags);
virtual void setRevoluteJointFlag(PxRevoluteJointFlag::Enum flag, bool value);
virtual PxRevoluteJointFlags getRevoluteJointFlags() const;
virtual void setProjectionLinearTolerance(PxReal distance);
virtual PxReal getProjectionLinearTolerance() const;
virtual void setProjectionAngularTolerance(PxReal tolerance);
virtual PxReal getProjectionAngularTolerance() const;
//~PxRevoluteJoint
bool attach(PxPhysics &physics, PxRigidActor* actor0, PxRigidActor* actor1);
static const PxConstraintShaderTable& getConstraintShaderTable() { return sShaders; }
virtual PxConstraintSolverPrep getPrep() const { return sShaders.solverPrep; }
private:
static PxConstraintShaderTable sShaders;
PX_FORCE_INLINE RevoluteJointData& data() const
{
return *static_cast<RevoluteJointData*>(mData);
}
};
} // namespace Ext
namespace Ext
{
// global function to share the joint shaders with API capture
extern "C" const PxConstraintShaderTable* GetRevoluteJointShaderTable();
}
}
#endif

View File

@ -0,0 +1,71 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "geometry/PxGeometryQuery.h"
#include "extensions/PxRigidActorExt.h"
#include "PxShape.h"
#include "PsAllocator.h"
#include "PsInlineArray.h"
#include "CmPhysXCommon.h"
using namespace physx;
PxBounds3* PxRigidActorExt::getRigidActorShapeLocalBoundsList(const PxRigidActor& actor, PxU32& numBounds)
{
const PxU32 numShapes = actor.getNbShapes();
if(numShapes == 0)
return NULL;
Ps::InlineArray<PxShape*, 64> shapes("PxShape*");
shapes.resize(numShapes);
actor.getShapes(shapes.begin(), shapes.size());
PxU32 numSqShapes = 0;
for(PxU32 i = 0; i < numShapes; i++)
{
if(shapes[i]->getFlags() & PxShapeFlag::eSCENE_QUERY_SHAPE)
numSqShapes++;
}
PxBounds3* bounds = reinterpret_cast<PxBounds3*>(PX_ALLOC(numSqShapes * sizeof(PxBounds3), "PxBounds3"));
numSqShapes = 0;
for(PxU32 i = 0; i < numShapes; i++)
{
if(shapes[i]->getFlags() & PxShapeFlag::eSCENE_QUERY_SHAPE)
{
bounds[numSqShapes++] = PxGeometryQuery::getWorldBounds(shapes[i]->getGeometry().any(), shapes[i]->getLocalPose(), 1.0f);
}
}
numBounds = numSqShapes;
return bounds;
}

View File

@ -0,0 +1,644 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "geometry/PxBoxGeometry.h"
#include "geometry/PxSphereGeometry.h"
#include "geometry/PxCapsuleGeometry.h"
#include "geometry/PxPlaneGeometry.h"
#include "geometry/PxConvexMeshGeometry.h"
#include "geometry/PxTriangleMeshGeometry.h"
#include "geometry/PxHeightFieldGeometry.h"
#include "geometry/PxGeometryHelpers.h"
#include "geometry/PxConvexMesh.h"
#include "extensions/PxRigidBodyExt.h"
#include "extensions/PxShapeExt.h"
#include "extensions/PxMassProperties.h"
#include "PxShape.h"
#include "PxScene.h"
#include "PxBatchQuery.h"
#include "PxRigidDynamic.h"
#include "PxRigidStatic.h"
#include "ExtInertiaTensor.h"
#include "PsAllocator.h"
#include "PsFoundation.h"
#include "CmUtils.h"
using namespace physx;
using namespace Cm;
static bool computeMassAndDiagInertia(Ext::InertiaTensorComputer& inertiaComp,
PxVec3& diagTensor, PxQuat& orient, PxReal& massOut, PxVec3& coM, bool lockCOM, const PxRigidBody& body, const char* errorStr)
{
// The inertia tensor and center of mass is relative to the actor at this point. Transform to the
// body frame directly if CoM is specified, else use computed center of mass
if (lockCOM)
{
inertiaComp.translate(-coM); // base the tensor on user's desired center of mass.
}
else
{
//get center of mass - has to be done BEFORE centering.
coM = inertiaComp.getCenterOfMass();
//the computed result now needs to be centered around the computed center of mass:
inertiaComp.center();
}
// The inertia matrix is now based on the body's center of mass desc.massLocalPose.p
massOut = inertiaComp.getMass();
diagTensor = PxDiagonalize(inertiaComp.getInertia(), orient);
if ((diagTensor.x > 0.0f) && (diagTensor.y > 0.0f) && (diagTensor.z > 0.0f))
return true;
else
{
Ps::getFoundation().error(PxErrorCode::eDEBUG_WARNING, __FILE__, __LINE__,
"%s: inertia tensor has negative components (ill-conditioned input expected). Approximation for inertia tensor will be used instead.", errorStr);
// keep center of mass but use the AABB as a crude approximation for the inertia tensor
PxBounds3 bounds = body.getWorldBounds();
PxTransform pose = body.getGlobalPose();
bounds = PxBounds3::transformFast(pose.getInverse(), bounds);
Ext::InertiaTensorComputer it(false);
it.setBox(bounds.getExtents());
it.scaleDensity(massOut / it.getMass());
PxMat33 inertia = it.getInertia();
diagTensor = PxVec3(inertia.column0.x, inertia.column1.y, inertia.column2.z);
orient = PxQuat(PxIdentity);
return true;
}
}
static bool computeMassAndInertia(bool multipleMassOrDensity, PxRigidBody& body, const PxReal* densities, const PxReal* masses, PxU32 densityOrMassCount, bool includeNonSimShapes, Ext::InertiaTensorComputer& computer)
{
PX_ASSERT(!densities || !masses);
PX_ASSERT((densities || masses) && (densityOrMassCount > 0));
Ext::InertiaTensorComputer inertiaComp(true);
Ps::InlineArray<PxShape*, 16> shapes("PxShape*"); shapes.resize(body.getNbShapes());
body.getShapes(shapes.begin(), shapes.size());
PxU32 validShapeIndex = 0;
PxReal currentMassOrDensity;
const PxReal* massOrDensityArray;
if (densities)
{
massOrDensityArray = densities;
currentMassOrDensity = densities[0];
}
else
{
massOrDensityArray = masses;
currentMassOrDensity = masses[0];
}
if (!PxIsFinite(currentMassOrDensity))
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"computeMassAndInertia: Provided mass or density has no valid value");
return false;
}
for(PxU32 i=0; i < shapes.size(); i++)
{
if ((!(shapes[i]->getFlags() & PxShapeFlag::eSIMULATION_SHAPE)) && (!includeNonSimShapes))
continue;
if (multipleMassOrDensity)
{
if (validShapeIndex < densityOrMassCount)
{
currentMassOrDensity = massOrDensityArray[validShapeIndex];
if (!PxIsFinite(currentMassOrDensity))
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"computeMassAndInertia: Provided mass or density has no valid value");
return false;
}
}
else
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"computeMassAndInertia: Not enough mass/density values provided for all (simulation) shapes");
return false;
}
}
Ext::InertiaTensorComputer it(false);
switch(shapes[i]->getGeometryType())
{
case PxGeometryType::eSPHERE :
{
PxSphereGeometry g;
bool ok = shapes[i]->getSphereGeometry(g);
PX_ASSERT(ok);
PX_UNUSED(ok);
PxTransform temp(shapes[i]->getLocalPose());
it.setSphere(g.radius, &temp);
}
break;
case PxGeometryType::eBOX :
{
PxBoxGeometry g;
bool ok = shapes[i]->getBoxGeometry(g);
PX_ASSERT(ok);
PX_UNUSED(ok);
PxTransform temp(shapes[i]->getLocalPose());
it.setBox(g.halfExtents, &temp);
}
break;
case PxGeometryType::eCAPSULE :
{
PxCapsuleGeometry g;
bool ok = shapes[i]->getCapsuleGeometry(g);
PX_ASSERT(ok);
PX_UNUSED(ok);
PxTransform temp(shapes[i]->getLocalPose());
it.setCapsule(0, g.radius, g.halfHeight, &temp);
}
break;
case PxGeometryType::eCONVEXMESH :
{
PxConvexMeshGeometry g;
bool ok = shapes[i]->getConvexMeshGeometry(g);
PX_ASSERT(ok);
PX_UNUSED(ok);
PxConvexMesh& convMesh = *g.convexMesh;
PxReal convMass;
PxMat33 convInertia;
PxVec3 convCoM;
convMesh.getMassInformation(convMass, reinterpret_cast<PxMat33&>(convInertia), convCoM);
if (!g.scale.isIdentity())
{
//scale the mass properties
convMass *= (g.scale.scale.x * g.scale.scale.y * g.scale.scale.z);
convCoM = g.scale.rotation.rotateInv(g.scale.scale.multiply(g.scale.rotation.rotate(convCoM)));
convInertia = PxMassProperties::scaleInertia(convInertia, g.scale.rotation, g.scale.scale);
}
it = Ext::InertiaTensorComputer(convInertia, convCoM, convMass);
it.transform(shapes[i]->getLocalPose());
}
break;
case PxGeometryType::eHEIGHTFIELD:
case PxGeometryType::ePLANE:
case PxGeometryType::eTRIANGLEMESH:
case PxGeometryType::eINVALID:
case PxGeometryType::eGEOMETRY_COUNT:
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"computeMassAndInertia: Dynamic actor with illegal collision shapes");
return false;
}
}
if (densities)
it.scaleDensity(currentMassOrDensity);
else if (multipleMassOrDensity) // mass per shape -> need to scale density per shape
it.scaleDensity(currentMassOrDensity / it.getMass());
inertiaComp.add(it);
validShapeIndex++;
}
if (validShapeIndex && masses && (!multipleMassOrDensity)) // at least one simulation shape and single mass for all shapes -> scale density at the end
{
inertiaComp.scaleDensity(currentMassOrDensity / inertiaComp.getMass());
}
computer = inertiaComp;
return true;
}
static bool updateMassAndInertia(bool multipleMassOrDensity, PxRigidBody& body, const PxReal* densities, PxU32 densityCount, const PxVec3* massLocalPose, bool includeNonSimShapes)
{
bool success;
// default values in case there were no shapes
PxReal massOut = 1.0f;
PxVec3 diagTensor(1.f,1.f,1.f);
PxQuat orient = PxQuat(PxIdentity);
bool lockCom = massLocalPose != NULL;
PxVec3 com = lockCom ? *massLocalPose : PxVec3(0);
const char* errorStr = "PxRigidBodyExt::updateMassAndInertia";
if (densities && densityCount)
{
Ext::InertiaTensorComputer inertiaComp(true);
if(computeMassAndInertia(multipleMassOrDensity, body, densities, NULL, densityCount, includeNonSimShapes, inertiaComp))
{
if(inertiaComp.getMass()!=0 && computeMassAndDiagInertia(inertiaComp, diagTensor, orient, massOut, com, lockCom, body, errorStr))
success = true;
else
success = false; // body with no shapes provided or computeMassAndDiagInertia() failed
}
else
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"%s: Mass and inertia computation failed, setting mass to 1 and inertia to (1,1,1)", errorStr);
success = false;
}
}
else
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"%s: No density specified, setting mass to 1 and inertia to (1,1,1)", errorStr);
success = false;
}
PX_ASSERT(orient.isFinite());
PX_ASSERT(diagTensor.isFinite());
PX_ASSERT(PxIsFinite(massOut));
body.setMass(massOut);
body.setMassSpaceInertiaTensor(diagTensor);
body.setCMassLocalPose(PxTransform(com, orient));
return success;
}
bool PxRigidBodyExt::updateMassAndInertia(PxRigidBody& body, const PxReal* densities, PxU32 densityCount, const PxVec3* massLocalPose, bool includeNonSimShapes)
{
return ::updateMassAndInertia(true, body, densities, densityCount, massLocalPose, includeNonSimShapes);
}
bool PxRigidBodyExt::updateMassAndInertia(PxRigidBody& body, PxReal density, const PxVec3* massLocalPose, bool includeNonSimShapes)
{
return ::updateMassAndInertia(false, body, &density, 1, massLocalPose, includeNonSimShapes);
}
static bool setMassAndUpdateInertia(bool multipleMassOrDensity, PxRigidBody& body, const PxReal* masses, PxU32 massCount, const PxVec3* massLocalPose, bool includeNonSimShapes)
{
bool success;
// default values in case there were no shapes
PxReal massOut = 1.0f;
PxVec3 diagTensor(1.0f,1.0f,1.0f);
PxQuat orient = PxQuat(PxIdentity);
bool lockCom = massLocalPose != NULL;
PxVec3 com = lockCom ? *massLocalPose : PxVec3(0);
const char* errorStr = "PxRigidBodyExt::setMassAndUpdateInertia";
if(masses && massCount)
{
Ext::InertiaTensorComputer inertiaComp(true);
if(computeMassAndInertia(multipleMassOrDensity, body, NULL, masses, massCount, includeNonSimShapes, inertiaComp))
{
success = true;
if (inertiaComp.getMass()!=0 && !computeMassAndDiagInertia(inertiaComp, diagTensor, orient, massOut, com, lockCom, body, errorStr))
success = false; // computeMassAndDiagInertia() failed (mass zero?)
if (massCount == 1)
massOut = masses[0]; // to cover special case where body has no simulation shape
}
else
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"%s: Mass and inertia computation failed, setting mass to 1 and inertia to (1,1,1)", errorStr);
success = false;
}
}
else
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"%s: No mass specified, setting mass to 1 and inertia to (1,1,1)", errorStr);
success = false;
}
PX_ASSERT(orient.isFinite());
PX_ASSERT(diagTensor.isFinite());
body.setMass(massOut);
body.setMassSpaceInertiaTensor(diagTensor);
body.setCMassLocalPose(PxTransform(com, orient));
return success;
}
bool PxRigidBodyExt::setMassAndUpdateInertia(PxRigidBody& body, const PxReal* masses, PxU32 massCount, const PxVec3* massLocalPose, bool includeNonSimShapes)
{
return ::setMassAndUpdateInertia(true, body, masses, massCount, massLocalPose, includeNonSimShapes);
}
bool PxRigidBodyExt::setMassAndUpdateInertia(PxRigidBody& body, PxReal mass, const PxVec3* massLocalPose, bool includeNonSimShapes)
{
return ::setMassAndUpdateInertia(false, body, &mass, 1, massLocalPose, includeNonSimShapes);
}
PxMassProperties PxRigidBodyExt::computeMassPropertiesFromShapes(const PxShape* const* shapes, PxU32 shapeCount)
{
Ps::InlineArray<PxMassProperties, 16> massProps;
massProps.reserve(shapeCount);
Ps::InlineArray<PxTransform, 16> localTransforms;
localTransforms.reserve(shapeCount);
for(PxU32 shapeIdx=0; shapeIdx < shapeCount; shapeIdx++)
{
const PxShape* shape = shapes[shapeIdx];
PxMassProperties mp(shape->getGeometry().any());
massProps.pushBack(mp);
localTransforms.pushBack(shape->getLocalPose());
}
return PxMassProperties::sum(massProps.begin(), localTransforms.begin(), shapeCount);
}
PX_INLINE void addForceAtPosInternal(PxRigidBody& body, const PxVec3& force, const PxVec3& pos, PxForceMode::Enum mode, bool wakeup)
{
if(mode == PxForceMode::eACCELERATION || mode == PxForceMode::eVELOCITY_CHANGE)
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"PxRigidBodyExt::addForce methods do not support eACCELERATION or eVELOCITY_CHANGE modes");
return;
}
const PxTransform globalPose = body.getGlobalPose();
const PxVec3 centerOfMass = globalPose.transform(body.getCMassLocalPose().p);
const PxVec3 torque = (pos - centerOfMass).cross(force);
body.addForce(force, mode, wakeup);
body.addTorque(torque, mode, wakeup);
}
void PxRigidBodyExt::addForceAtPos(PxRigidBody& body, const PxVec3& force, const PxVec3& pos, PxForceMode::Enum mode, bool wakeup)
{
addForceAtPosInternal(body, force, pos, mode, wakeup);
}
void PxRigidBodyExt::addForceAtLocalPos(PxRigidBody& body, const PxVec3& force, const PxVec3& pos, PxForceMode::Enum mode, bool wakeup)
{
//transform pos to world space
const PxVec3 globalForcePos = body.getGlobalPose().transform(pos);
addForceAtPosInternal(body, force, globalForcePos, mode, wakeup);
}
void PxRigidBodyExt::addLocalForceAtPos(PxRigidBody& body, const PxVec3& force, const PxVec3& pos, PxForceMode::Enum mode, bool wakeup)
{
const PxVec3 globalForce = body.getGlobalPose().rotate(force);
addForceAtPosInternal(body, globalForce, pos, mode, wakeup);
}
void PxRigidBodyExt::addLocalForceAtLocalPos(PxRigidBody& body, const PxVec3& force, const PxVec3& pos, PxForceMode::Enum mode, bool wakeup)
{
const PxTransform globalPose = body.getGlobalPose();
const PxVec3 globalForcePos = globalPose.transform(pos);
const PxVec3 globalForce = globalPose.rotate(force);
addForceAtPosInternal(body, globalForce, globalForcePos, mode, wakeup);
}
PX_INLINE PxVec3 getVelocityAtPosInternal(const PxRigidBody& body, const PxVec3& point)
{
PxVec3 velocity = body.getLinearVelocity();
velocity += body.getAngularVelocity().cross(point);
return velocity;
}
PxVec3 PxRigidBodyExt::getVelocityAtPos(const PxRigidBody& body, const PxVec3& point)
{
const PxTransform globalPose = body.getGlobalPose();
const PxVec3 centerOfMass = globalPose.transform(body.getCMassLocalPose().p);
const PxVec3 rpoint = point - centerOfMass;
return getVelocityAtPosInternal(body, rpoint);
}
PxVec3 PxRigidBodyExt::getLocalVelocityAtLocalPos(const PxRigidBody& body, const PxVec3& point)
{
const PxTransform globalPose = body.getGlobalPose();
const PxVec3 centerOfMass = globalPose.transform(body.getCMassLocalPose().p);
const PxVec3 rpoint = globalPose.transform(point) - centerOfMass;
return getVelocityAtPosInternal(body, rpoint);
}
PxVec3 PxRigidBodyExt::getVelocityAtOffset(const PxRigidBody& body, const PxVec3& point)
{
const PxTransform globalPose = body.getGlobalPose();
const PxVec3 centerOfMass = globalPose.rotate(body.getCMassLocalPose().p);
const PxVec3 rpoint = point - centerOfMass;
return getVelocityAtPosInternal(body, rpoint);
}
void PxRigidBodyExt::computeVelocityDeltaFromImpulse(const PxRigidBody& body, const PxTransform& globalPose, const PxVec3& point, const PxVec3& impulse, const PxReal invMassScale,
const PxReal invInertiaScale, PxVec3& linearVelocityChange, PxVec3& angularVelocityChange)
{
const PxVec3 centerOfMass = globalPose.transform(body.getCMassLocalPose().p);
const PxReal invMass = body.getInvMass() * invMassScale;
const PxVec3 invInertiaMS = body.getMassSpaceInvInertiaTensor() * invInertiaScale;
PxMat33 invInertia;
transformInertiaTensor(invInertiaMS, PxMat33(globalPose.q), invInertia);
linearVelocityChange = impulse * invMass;
const PxVec3 rXI = (point - centerOfMass).cross(impulse);
angularVelocityChange = invInertia * rXI;
}
void PxRigidBodyExt::computeLinearAngularImpulse(const PxRigidBody& body, const PxTransform& globalPose, const PxVec3& point, const PxVec3& impulse, const PxReal invMassScale,
const PxReal invInertiaScale, PxVec3& linearImpulse, PxVec3& angularImpulse)
{
const PxVec3 centerOfMass = globalPose.transform(body.getCMassLocalPose().p);
linearImpulse = impulse * invMassScale;
angularImpulse = (point - centerOfMass).cross(impulse) * invInertiaScale;
}
//=================================================================================
// Single closest hit compound sweep
bool PxRigidBodyExt::linearSweepSingle(
PxRigidBody& body, PxScene& scene, const PxVec3& unitDir, const PxReal distance,
PxHitFlags outputFlags, PxSweepHit& closestHit, PxU32& shapeIndex,
const PxQueryFilterData& filterData, PxQueryFilterCallback* filterCall,
const PxQueryCache* cache, const PxReal inflation)
{
shapeIndex = 0xFFFFffff;
PxReal closestDist = distance;
PxU32 nbShapes = body.getNbShapes();
for(PxU32 i=0; i < nbShapes; i++)
{
PxShape* shape = NULL;
body.getShapes(&shape, 1, i);
PX_ASSERT(shape != NULL);
PxTransform pose = PxShapeExt::getGlobalPose(*shape, body);
PxQueryFilterData fd;
fd.flags = filterData.flags;
PxU32 or4 = (filterData.data.word0 | filterData.data.word1 | filterData.data.word2 | filterData.data.word3);
fd.data = or4 ? filterData.data : shape->getQueryFilterData();
PxGeometryHolder anyGeom = shape->getGeometry();
PxSweepBuffer subHit; // touching hits are not allowed to be returned from the filters
scene.sweep(anyGeom.any(), pose, unitDir, distance, subHit, outputFlags, fd, filterCall, cache, inflation);
if (subHit.hasBlock && subHit.block.distance < closestDist)
{
closestDist = subHit.block.distance;
closestHit = subHit.block;
shapeIndex = i;
}
}
return (shapeIndex != 0xFFFFffff);
}
//=================================================================================
// Multiple hits compound sweep
// AP: we might be able to improve the return results API but no time for it in 3.3
PxU32 PxRigidBodyExt::linearSweepMultiple(
PxRigidBody& body, PxScene& scene, const PxVec3& unitDir, const PxReal distance, PxHitFlags outputFlags,
PxSweepHit* hitBuffer, PxU32* hitShapeIndices, PxU32 hitBufferSize, PxSweepHit& block, PxI32& blockingHitShapeIndex,
bool& overflow, const PxQueryFilterData& filterData, PxQueryFilterCallback* filterCall,
const PxQueryCache* cache, const PxReal inflation)
{
overflow = false;
blockingHitShapeIndex = -1;
for (PxU32 i = 0; i < hitBufferSize; i++)
hitShapeIndices[i] = 0xFFFFffff;
PxI32 sumNbResults = 0;
PxU32 nbShapes = body.getNbShapes();
PxF32 shrunkMaxDistance = distance;
for(PxU32 i=0; i < nbShapes; i++)
{
PxShape* shape = NULL;
body.getShapes(&shape, 1, i);
PX_ASSERT(shape != NULL);
PxTransform pose = PxShapeExt::getGlobalPose(*shape, body);
PxQueryFilterData fd;
fd.flags = filterData.flags;
PxU32 or4 = (filterData.data.word0 | filterData.data.word1 | filterData.data.word2 | filterData.data.word3);
fd.data = or4 ? filterData.data : shape->getQueryFilterData();
PxGeometryHolder anyGeom = shape->getGeometry();
PxU32 bufSizeLeft = hitBufferSize-sumNbResults;
PxSweepHit extraHit;
PxSweepBuffer buffer(bufSizeLeft == 0 ? &extraHit : hitBuffer+sumNbResults, bufSizeLeft == 0 ? 1 : hitBufferSize-sumNbResults);
scene.sweep(anyGeom.any(), pose, unitDir, shrunkMaxDistance, buffer, outputFlags, fd, filterCall, cache, inflation);
// Check and abort on overflow. Assume overflow if result count is bufSize.
PxU32 nbNewResults = buffer.getNbTouches();
overflow |= (nbNewResults >= bufSizeLeft);
if (bufSizeLeft == 0) // this is for when we used the extraHit buffer
nbNewResults = 0;
// set hitShapeIndices for each new non-blocking hit
for (PxU32 j = 0; j < nbNewResults; j++)
if (sumNbResults + PxU32(j) < hitBufferSize)
hitShapeIndices[sumNbResults+j] = i;
if (buffer.hasBlock) // there's a blocking hit in the most recent sweepMultiple results
{
// overwrite the return result blocking hit with the new blocking hit if under
if (blockingHitShapeIndex == -1 || buffer.block.distance < block.distance)
{
blockingHitShapeIndex = PxI32(i);
block = buffer.block;
}
// Remove all the old touching hits below the new maxDist
// sumNbResults is not updated yet at this point
// and represents the count accumulated so far excluding the very last query
PxI32 nbNewResultsSigned = PxI32(nbNewResults); // need a signed version, see nbNewResultsSigned-- below
for (PxI32 j = sumNbResults-1; j >= 0; j--) // iterate over "old" hits (up to shapeIndex-1)
if (buffer.block.distance < hitBuffer[j].distance)
{
// overwrite with last "new" hit
PxI32 sourceIndex = PxI32(sumNbResults)+nbNewResultsSigned-1; PX_ASSERT(sourceIndex >= j);
hitBuffer[j] = hitBuffer[sourceIndex];
hitShapeIndices[j] = hitShapeIndices[sourceIndex];
nbNewResultsSigned--; // can get negative, that means we are shifting the last results array
}
sumNbResults += nbNewResultsSigned;
} else // if there was no new blocking hit we don't need to do anything special, simply append all results to touch array
sumNbResults += nbNewResults;
PX_ASSERT(sumNbResults >= 0 && sumNbResults <= PxI32(hitBufferSize));
}
return PxU32(sumNbResults);
}
void PxRigidBodyExt::computeVelocityDeltaFromImpulse(const PxRigidBody& body, const PxVec3& impulsiveForce, const PxVec3& impulsiveTorque, PxVec3& deltaLinearVelocity, PxVec3& deltaAngularVelocity)
{
{
const PxF32 recipMass = body.getInvMass();
deltaLinearVelocity = impulsiveForce*recipMass;
}
{
const PxTransform globalPose = body.getGlobalPose();
const PxTransform cmLocalPose = body.getCMassLocalPose();
const PxTransform body2World = globalPose*cmLocalPose;
PxMat33 M(body2World.q);
const PxVec3 recipInertiaBodySpace = body.getMassSpaceInvInertiaTensor();
PxMat33 recipInertiaWorldSpace;
const float axx = recipInertiaBodySpace.x*M(0,0), axy = recipInertiaBodySpace.x*M(1,0), axz = recipInertiaBodySpace.x*M(2,0);
const float byx = recipInertiaBodySpace.y*M(0,1), byy = recipInertiaBodySpace.y*M(1,1), byz = recipInertiaBodySpace.y*M(2,1);
const float czx = recipInertiaBodySpace.z*M(0,2), czy = recipInertiaBodySpace.z*M(1,2), czz = recipInertiaBodySpace.z*M(2,2);
recipInertiaWorldSpace(0,0) = axx*M(0,0) + byx*M(0,1) + czx*M(0,2);
recipInertiaWorldSpace(1,1) = axy*M(1,0) + byy*M(1,1) + czy*M(1,2);
recipInertiaWorldSpace(2,2) = axz*M(2,0) + byz*M(2,1) + czz*M(2,2);
recipInertiaWorldSpace(0,1) = recipInertiaWorldSpace(1,0) = axx*M(1,0) + byx*M(1,1) + czx*M(1,2);
recipInertiaWorldSpace(0,2) = recipInertiaWorldSpace(2,0) = axx*M(2,0) + byx*M(2,1) + czx*M(2,2);
recipInertiaWorldSpace(1,2) = recipInertiaWorldSpace(2,1) = axy*M(2,0) + byy*M(2,1) + czy*M(2,2);
deltaAngularVelocity = recipInertiaWorldSpace*(impulsiveTorque);
}
}

View File

@ -0,0 +1,188 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "extensions/PxSceneQueryExt.h"
using namespace physx;
bool PxSceneQueryExt::raycastAny( const PxScene& scene,
const PxVec3& origin, const PxVec3& unitDir, const PxReal distance,
PxSceneQueryHit& hit, const PxSceneQueryFilterData& filterData,
PxSceneQueryFilterCallback* filterCall, const PxSceneQueryCache* cache)
{
PxSceneQueryFilterData fdAny = filterData;
fdAny.flags |= PxQueryFlag::eANY_HIT;
PxRaycastBuffer buf;
scene.raycast(origin, unitDir, distance, buf, PxHitFlag::eMESH_ANY, fdAny, filterCall, cache);
hit = buf.block;
return buf.hasBlock;
}
bool PxSceneQueryExt::raycastSingle(const PxScene& scene,
const PxVec3& origin, const PxVec3& unitDir, const PxReal distance,
PxSceneQueryFlags outputFlags, PxRaycastHit& hit,
const PxSceneQueryFilterData& filterData,
PxSceneQueryFilterCallback* filterCall, const PxSceneQueryCache* cache)
{
PxRaycastBuffer buf;
PxQueryFilterData fd1 = filterData;
scene.raycast(origin, unitDir, distance, buf, outputFlags, fd1, filterCall, cache);
hit = buf.block;
return buf.hasBlock;
}
PxI32 PxSceneQueryExt::raycastMultiple( const PxScene& scene,
const PxVec3& origin, const PxVec3& unitDir, const PxReal distance,
PxSceneQueryFlags outputFlags,
PxRaycastHit* hitBuffer, PxU32 hitBufferSize, bool& blockingHit,
const PxSceneQueryFilterData& filterData,
PxSceneQueryFilterCallback* filterCall, const PxSceneQueryCache* cache)
{
PxRaycastBuffer buf(hitBuffer, hitBufferSize);
PxQueryFilterData fd1 = filterData;
scene.raycast(origin, unitDir, distance, buf, outputFlags, fd1, filterCall, cache);
blockingHit = buf.hasBlock;
if(blockingHit)
{
if(buf.nbTouches < hitBufferSize)
{
hitBuffer[buf.nbTouches] = buf.block;
return PxI32(buf.nbTouches+1);
}
else // overflow, drop the last touch
{
hitBuffer[hitBufferSize-1] = buf.block;
return -1;
}
} else
// no block
return PxI32(buf.nbTouches);
}
bool PxSceneQueryExt::sweepAny( const PxScene& scene,
const PxGeometry& geometry, const PxTransform& pose, const PxVec3& unitDir, const PxReal distance,
PxSceneQueryFlags queryFlags,
PxSceneQueryHit& hit,
const PxSceneQueryFilterData& filterData,
PxSceneQueryFilterCallback* filterCall,
const PxSceneQueryCache* cache,
PxReal inflation)
{
PxSceneQueryFilterData fdAny = filterData;
fdAny.flags |= PxQueryFlag::eANY_HIT;
PxSweepBuffer buf;
scene.sweep(geometry, pose, unitDir, distance, buf, queryFlags, fdAny, filterCall, cache, inflation);
hit = buf.block;
return buf.hasBlock;
}
bool PxSceneQueryExt::sweepSingle( const PxScene& scene,
const PxGeometry& geometry, const PxTransform& pose, const PxVec3& unitDir, const PxReal distance,
PxSceneQueryFlags outputFlags,
PxSweepHit& hit,
const PxSceneQueryFilterData& filterData,
PxSceneQueryFilterCallback* filterCall,
const PxSceneQueryCache* cache,
PxReal inflation)
{
PxSweepBuffer buf;
PxQueryFilterData fd1 = filterData;
scene.sweep(geometry, pose, unitDir, distance, buf, outputFlags, fd1, filterCall, cache, inflation);
hit = buf.block;
return buf.hasBlock;
}
PxI32 PxSceneQueryExt::sweepMultiple( const PxScene& scene,
const PxGeometry& geometry, const PxTransform& pose, const PxVec3& unitDir, const PxReal distance,
PxSceneQueryFlags outputFlags, PxSweepHit* hitBuffer, PxU32 hitBufferSize, bool& blockingHit,
const PxSceneQueryFilterData& filterData,
PxSceneQueryFilterCallback* filterCall, const PxSceneQueryCache* cache,
PxReal inflation)
{
PxQueryFilterData fd1 = filterData;
PxSweepBuffer buf(hitBuffer, hitBufferSize);
scene.sweep(geometry, pose, unitDir, distance, buf, outputFlags, fd1, filterCall, cache, inflation);
blockingHit = buf.hasBlock;
if(blockingHit)
{
if(buf.nbTouches < hitBufferSize)
{
hitBuffer[buf.nbTouches] = buf.block;
return PxI32(buf.nbTouches+1);
}
else // overflow, drop the last touch
{
hitBuffer[hitBufferSize-1] = buf.block;
return -1;
}
} else
// no block
return PxI32(buf.nbTouches);
}
PxI32 PxSceneQueryExt::overlapMultiple( const PxScene& scene,
const PxGeometry& geometry, const PxTransform& pose,
PxOverlapHit* hitBuffer, PxU32 hitBufferSize,
const PxSceneQueryFilterData& filterData,
PxSceneQueryFilterCallback* filterCall)
{
PxQueryFilterData fd1 = filterData;
fd1.flags |= PxQueryFlag::eNO_BLOCK;
PxOverlapBuffer buf(hitBuffer, hitBufferSize);
scene.overlap(geometry, pose, buf, fd1, filterCall);
if(buf.hasBlock)
{
if(buf.nbTouches < hitBufferSize)
{
hitBuffer[buf.nbTouches] = buf.block;
return PxI32(buf.nbTouches+1);
}
else // overflow, drop the last touch
{
hitBuffer[hitBufferSize-1] = buf.block;
return -1;
}
} else
// no block
return PxI32(buf.nbTouches);
}
bool PxSceneQueryExt::overlapAny( const PxScene& scene,
const PxGeometry& geometry, const PxTransform& pose,
PxOverlapHit& hit,
const PxSceneQueryFilterData& filterData,
PxSceneQueryFilterCallback* filterCall)
{
PxSceneQueryFilterData fdAny = filterData;
fdAny.flags |= (PxQueryFlag::eANY_HIT | PxQueryFlag::eNO_BLOCK);
PxOverlapBuffer buf;
scene.overlap(geometry, pose, buf, fdAny, filterCall);
hit = buf.block;
return buf.hasBlock;
}

View File

@ -0,0 +1,44 @@
//
// 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-2021 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 EXT_SERIALIZATION_H
#define EXT_SERIALIZATION_H
namespace physx
{
namespace Ext
{
void RegisterExtensionsSerializers(PxSerializationRegistry& sr);
void UnregisterExtensionsSerializers(PxSerializationRegistry& sr);
void GetExtensionsBinaryMetaData(PxOutputStream& stream);
}
}
#endif

View File

@ -0,0 +1,156 @@
//
// 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-2021 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_NP_SHARED_QUEUE_ENTRY_POOL_H
#define PX_PHYSICS_EXTENSIONS_NP_SHARED_QUEUE_ENTRY_POOL_H
#include "CmPhysXCommon.h"
#include "PsAllocator.h"
#include "PsArray.h"
#include "PsSList.h"
namespace physx
{
namespace Ext
{
class SharedQueueEntry : public Ps::SListEntry
{
public:
SharedQueueEntry(void* objectRef) : mObjectRef(objectRef), mPooledEntry(false) {}
SharedQueueEntry() : mObjectRef(NULL), mPooledEntry(true) {}
public:
void* mObjectRef;
bool mPooledEntry; // True if the entry was preallocated in a pool
};
#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 // Because of the SList member I assume*/
template<class Alloc = typename Ps::AllocatorTraits<SharedQueueEntry>::Type >
class SharedQueueEntryPool : private Alloc
{
public:
SharedQueueEntryPool(PxU32 poolSize, const Alloc& alloc = Alloc(PX_DEBUG_EXP("SharedQueueEntryPool")));
~SharedQueueEntryPool();
SharedQueueEntry* getEntry(void* objectRef);
void putEntry(SharedQueueEntry& entry);
private:
SharedQueueEntry* mTaskEntryPool;
Ps::SList mTaskEntryPtrPool;
};
#if PX_VC
#pragma warning(pop)
#endif
} // namespace Ext
template <class Alloc>
Ext::SharedQueueEntryPool<Alloc>::SharedQueueEntryPool(PxU32 poolSize, const Alloc& alloc)
: Alloc(alloc)
{
Ps::AlignedAllocator<PX_SLIST_ALIGNMENT, Alloc> alignedAlloc("SharedQueueEntryPool");
mTaskEntryPool = poolSize ? reinterpret_cast<SharedQueueEntry*>(alignedAlloc.allocate(sizeof(SharedQueueEntry) * poolSize, __FILE__, __LINE__)) : NULL;
if (mTaskEntryPool)
{
for(PxU32 i=0; i < poolSize; i++)
{
PX_ASSERT((size_t(&mTaskEntryPool[i]) & (PX_SLIST_ALIGNMENT-1)) == 0); // The SList entry must be aligned according to PX_SLIST_ALIGNMENT
PX_PLACEMENT_NEW(&mTaskEntryPool[i], SharedQueueEntry)();
PX_ASSERT(mTaskEntryPool[i].mPooledEntry == true);
mTaskEntryPtrPool.push(mTaskEntryPool[i]);
}
}
}
template <class Alloc>
Ext::SharedQueueEntryPool<Alloc>::~SharedQueueEntryPool()
{
if (mTaskEntryPool)
{
Ps::AlignedAllocator<PX_SLIST_ALIGNMENT, Alloc> alignedAlloc("SharedQueueEntryPool");
alignedAlloc.deallocate(mTaskEntryPool);
}
}
template <class Alloc>
Ext::SharedQueueEntry* Ext::SharedQueueEntryPool<Alloc>::getEntry(void* objectRef)
{
SharedQueueEntry* e = static_cast<SharedQueueEntry*>(mTaskEntryPtrPool.pop());
if (e)
{
PX_ASSERT(e->mPooledEntry == true);
e->mObjectRef = objectRef;
return e;
}
else
{
Ps::AlignedAllocator<PX_SLIST_ALIGNMENT, Alloc> alignedAlloc;
e = reinterpret_cast<SharedQueueEntry*>(alignedAlloc.allocate(sizeof(SharedQueueEntry), __FILE__, __LINE__));
if (e)
{
PX_PLACEMENT_NEW(e, SharedQueueEntry)(objectRef);
PX_ASSERT(e->mPooledEntry == false);
}
return e;
}
}
template <class Alloc>
void Ext::SharedQueueEntryPool<Alloc>::putEntry(Ext::SharedQueueEntry& entry)
{
if (entry.mPooledEntry)
{
entry.mObjectRef = NULL;
mTaskEntryPtrPool.push(entry);
}
else
{
Ps::AlignedAllocator<PX_SLIST_ALIGNMENT, Alloc> alignedAlloc;
alignedAlloc.deallocate(&entry);
}
}
}
#endif

View File

@ -0,0 +1,384 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "foundation/PxMathUtils.h"
#include "foundation/PxQuat.h"
#include "geometry/PxSphereGeometry.h"
#include "geometry/PxBoxGeometry.h"
#include "geometry/PxCapsuleGeometry.h"
#include "geometry/PxConvexMeshGeometry.h"
#include "geometry/PxPlaneGeometry.h"
#include "extensions/PxRigidBodyExt.h"
#include "extensions/PxSimpleFactory.h"
#include "PxPhysics.h"
#include "PxScene.h"
#include "PxRigidStatic.h"
#include "PxRigidStatic.h"
#include "PxRigidDynamic.h"
#include "PxShape.h"
#include "CmPhysXCommon.h"
#include "PsFoundation.h"
#include "PsUtilities.h"
#include "PsInlineArray.h"
using namespace physx;
using namespace shdfnd;
namespace
{
bool isDynamicGeometry(PxGeometryType::Enum type)
{
return type == PxGeometryType::eBOX
|| type == PxGeometryType::eSPHERE
|| type == PxGeometryType::eCAPSULE
|| type == PxGeometryType::eCONVEXMESH;
}
}
namespace physx
{
PxRigidDynamic* PxCreateDynamic(PxPhysics& sdk,
const PxTransform& transform,
PxShape& shape,
PxReal density)
{
PX_CHECK_AND_RETURN_NULL(transform.isValid(), "PxCreateDynamic: transform is not valid.");
PxRigidDynamic* actor = sdk.createRigidDynamic(transform);
if(actor)
{
actor->attachShape(shape);
PxRigidBodyExt::updateMassAndInertia(*actor, density);
}
return actor;
}
PxRigidDynamic* PxCreateDynamic(PxPhysics& sdk,
const PxTransform& transform,
const PxGeometry& geometry,
PxMaterial& material,
PxReal density,
const PxTransform& shapeOffset)
{
PX_CHECK_AND_RETURN_NULL(transform.isValid(), "PxCreateDynamic: transform is not valid.");
PX_CHECK_AND_RETURN_NULL(shapeOffset.isValid(), "PxCreateDynamic: shapeOffset is not valid.");
if(!isDynamicGeometry(geometry.getType()) || density <= 0.0f)
return NULL;
PxShape* shape = sdk.createShape(geometry, material, true);
if(!shape)
return NULL;
shape->setLocalPose(shapeOffset);
PxRigidDynamic* body = shape ? PxCreateDynamic(sdk, transform, *shape, density) : NULL;
shape->release();
return body;
}
PxRigidDynamic* PxCreateKinematic(PxPhysics& sdk,
const PxTransform& transform,
PxShape& shape,
PxReal density)
{
PX_CHECK_AND_RETURN_NULL(transform.isValid(), "PxCreateKinematic: transform is not valid.");
bool isDynGeom = isDynamicGeometry(shape.getGeometryType());
if(isDynGeom && density <= 0.0f)
return NULL;
PxRigidDynamic* actor = sdk.createRigidDynamic(transform);
if(actor)
{
actor->setRigidBodyFlag(PxRigidBodyFlag::eKINEMATIC, true);
if(!isDynGeom)
shape.setFlag(PxShapeFlag::eSIMULATION_SHAPE, false);
actor->attachShape(shape);
if(isDynGeom)
PxRigidBodyExt::updateMassAndInertia(*actor, density);
else
{
actor->setMass(1.f);
actor->setMassSpaceInertiaTensor(PxVec3(1.f,1.f,1.f));
}
}
return actor;
}
PxRigidDynamic* PxCreateKinematic(PxPhysics& sdk,
const PxTransform& transform,
const PxGeometry& geometry,
PxMaterial& material,
PxReal density,
const PxTransform& shapeOffset)
{
PX_CHECK_AND_RETURN_NULL(transform.isValid(), "PxCreateKinematic: transform is not valid.");
PX_CHECK_AND_RETURN_NULL(shapeOffset.isValid(), "PxCreateKinematic: shapeOffset is not valid.");
bool isDynGeom = isDynamicGeometry(geometry.getType());
if(isDynGeom && density <= 0.0f)
return NULL;
PxShape* shape = sdk.createShape(geometry, material, true);
if(!shape)
return NULL;
shape->setLocalPose(shapeOffset);
PxRigidDynamic* body = PxCreateKinematic(sdk, transform, *shape, density);
shape->release();
return body;
}
PxRigidStatic* PxCreateStatic(PxPhysics& sdk,
const PxTransform& transform,
PxShape& shape)
{
PX_CHECK_AND_RETURN_NULL(transform.isValid(), "PxCreateStatic: transform is not valid.");
PxRigidStatic* s = sdk.createRigidStatic(transform);
if(s)
s->attachShape(shape);
return s;
}
PxRigidStatic* PxCreateStatic(PxPhysics& sdk,
const PxTransform& transform,
const PxGeometry& geometry,
PxMaterial& material,
const PxTransform& shapeOffset)
{
PX_CHECK_AND_RETURN_NULL(transform.isValid(), "PxCreateStatic: transform is not valid.");
PX_CHECK_AND_RETURN_NULL(shapeOffset.isValid(), "PxCreateStatic: shapeOffset is not valid.");
PxShape* shape = sdk.createShape(geometry, material, true);
if(!shape)
return NULL;
shape->setLocalPose(shapeOffset);
PxRigidStatic* s = PxCreateStatic(sdk, transform, *shape);
shape->release();
return s;
}
PxRigidStatic* PxCreatePlane(PxPhysics& sdk,
const PxPlane& plane,
PxMaterial& material)
{
PX_CHECK_AND_RETURN_NULL(plane.n.isFinite(), "PxCreatePlane: plane normal is not valid.");
if (!plane.n.isNormalized())
return NULL;
return PxCreateStatic(sdk, PxTransformFromPlaneEquation(plane), PxPlaneGeometry(), material);
}
PxShape* PxCloneShape(PxPhysics &physics, const PxShape& from, bool isExclusive)
{
Ps::InlineArray<PxMaterial*, 64> materials;
PxU16 materialCount = from.getNbMaterials();
materials.resize(materialCount);
from.getMaterials(materials.begin(), materialCount);
PxShape* to = physics.createShape(from.getGeometry().any(), materials.begin(), materialCount, isExclusive, from.getFlags());
to->setLocalPose(from.getLocalPose());
to->setContactOffset(from.getContactOffset());
to->setRestOffset(from.getRestOffset());
to->setSimulationFilterData(from.getSimulationFilterData());
to->setQueryFilterData(from.getQueryFilterData());
return to;
}
namespace
{
void copyStaticProperties(PxPhysics& physics, PxRigidActor& to, const PxRigidActor& from)
{
Ps::InlineArray<PxShape*, 64> shapes;
shapes.resize(from.getNbShapes());
PxU32 shapeCount = from.getNbShapes();
from.getShapes(shapes.begin(), shapeCount);
for(PxU32 i = 0; i < shapeCount; i++)
{
PxShape* s = shapes[i];
if(!s->isExclusive())
to.attachShape(*s);
else
{
PxShape* newShape = physx::PxCloneShape(physics, *s, true);
to.attachShape(*newShape);
newShape->release();
}
}
to.setActorFlags(from.getActorFlags());
to.setOwnerClient(from.getOwnerClient());
to.setDominanceGroup(from.getDominanceGroup());
}
}
PxRigidStatic* PxCloneStatic(PxPhysics& physicsSDK,
const PxTransform& transform,
const PxRigidActor& from)
{
PxRigidStatic* to = physicsSDK.createRigidStatic(transform);
if(!to)
return NULL;
copyStaticProperties(physicsSDK, *to, from);
return to;
}
PxRigidDynamic* PxCloneDynamic(PxPhysics& physicsSDK,
const PxTransform& transform,
const PxRigidDynamic& from)
{
PxRigidDynamic* to = physicsSDK.createRigidDynamic(transform);
if(!to)
return NULL;
copyStaticProperties(physicsSDK, *to, from);
to->setRigidBodyFlags(from.getRigidBodyFlags());
to->setMass(from.getMass());
to->setMassSpaceInertiaTensor(from.getMassSpaceInertiaTensor());
to->setCMassLocalPose(from.getCMassLocalPose());
to->setLinearVelocity(from.getLinearVelocity());
to->setAngularVelocity(from.getAngularVelocity());
to->setLinearDamping(from.getAngularDamping());
to->setAngularDamping(from.getAngularDamping());
PxU32 posIters, velIters;
from.getSolverIterationCounts(posIters, velIters);
to->setSolverIterationCounts(posIters, velIters);
to->setMaxAngularVelocity(from.getMaxAngularVelocity());
to->setMaxDepenetrationVelocity(from.getMaxDepenetrationVelocity());
to->setSleepThreshold(from.getSleepThreshold());
to->setStabilizationThreshold(from.getStabilizationThreshold());
to->setMinCCDAdvanceCoefficient(from.getMinCCDAdvanceCoefficient());
to->setContactReportThreshold(from.getContactReportThreshold());
to->setMaxContactImpulse(from.getMaxContactImpulse());
return to;
}
namespace
{
PxTransform scalePosition(const PxTransform& t, PxReal scale)
{
return PxTransform(t.p*scale, t.q);
}
}
void PxScaleRigidActor(PxRigidActor& actor, PxReal scale, bool scaleMassProps)
{
PX_CHECK_AND_RETURN(scale > 0,
"PxScaleRigidActor requires that the scale parameter is greater than zero");
Ps::InlineArray<PxShape*, 64> shapes;
shapes.resize(actor.getNbShapes());
actor.getShapes(shapes.begin(), shapes.size());
for(PxU32 i=0;i<shapes.size();i++)
{
shapes[i]->setLocalPose(scalePosition(shapes[i]->getLocalPose(), scale));
PxGeometryHolder h = shapes[i]->getGeometry();
switch(h.getType())
{
case PxGeometryType::eSPHERE:
h.sphere().radius *= scale;
break;
case PxGeometryType::ePLANE:
break;
case PxGeometryType::eCAPSULE:
h.capsule().halfHeight *= scale;
h.capsule().radius *= scale;
break;
case PxGeometryType::eBOX:
h.box().halfExtents *= scale;
break;
case PxGeometryType::eCONVEXMESH:
h.convexMesh().scale.scale *= scale;
break;
case PxGeometryType::eTRIANGLEMESH:
h.triangleMesh().scale.scale *= scale;
break;
case PxGeometryType::eHEIGHTFIELD:
h.heightField().heightScale *= scale;
h.heightField().rowScale *= scale;
h.heightField().columnScale *= scale;
break;
case PxGeometryType::eINVALID:
case PxGeometryType::eGEOMETRY_COUNT:
PX_ASSERT(0);
}
shapes[i]->setGeometry(h.any());
}
if(!scaleMassProps)
return;
PxRigidDynamic* dynamic = (&actor)->is<PxRigidDynamic>();
if(!dynamic)
return;
PxReal scale3 = scale*scale*scale;
dynamic->setMass(dynamic->getMass()*scale3);
dynamic->setMassSpaceInertiaTensor(dynamic->getMassSpaceInertiaTensor()*scale3*scale*scale);
dynamic->setCMassLocalPose(scalePosition(dynamic->getCMassLocalPose(), scale));
}
}

View File

@ -0,0 +1,146 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "foundation/PxMemory.h"
#include "extensions/PxSmoothNormals.h"
#include "PsMathUtils.h"
#include "PsUserAllocated.h"
#include "PsUtilities.h"
#include "CmPhysXCommon.h"
using namespace physx;
static PxReal computeAngle(const PxVec3* verts, const PxU32* refs, PxU32 vref)
{
PxU32 e0=0,e2=0;
if(vref==refs[0])
{
e0 = 2;
e2 = 1;
}
else if(vref==refs[1])
{
e0 = 2;
e2 = 0;
}
else if(vref==refs[2])
{
e0 = 0;
e2 = 1;
}
else
{
PX_ASSERT(0);
}
const PxVec3 edge0 = verts[refs[e0]] - verts[vref];
const PxVec3 edge1 = verts[refs[e2]] - verts[vref];
return Ps::angle(edge0, edge1);
}
bool PxBuildSmoothNormals(PxU32 nbTris, PxU32 nbVerts, const PxVec3* verts, const PxU32* dFaces, const PxU16* wFaces, PxVec3* normals, bool flip)
{
if(!verts || !normals || !nbTris || !nbVerts)
return false;
// Get correct destination buffers
// - if available, write directly to user-provided buffers
// - else get some ram and keep track of it
PxVec3* FNormals = reinterpret_cast<PxVec3*>(PX_ALLOC_TEMP(sizeof(PxVec3)*nbTris, "PxVec3"));
if(!FNormals) return false;
// Compute face normals
const PxU32 c = PxU32(flip!=0);
for(PxU32 i=0; i<nbTris; i++)
{
// compute indices outside of array index to workaround
// SNC bug which was generating incorrect addresses
const PxU32 i0 = i*3+0;
const PxU32 i1 = i*3+1+c;
const PxU32 i2 = i*3+2-c;
const PxU32 Ref0 = dFaces ? dFaces[i0] : wFaces ? wFaces[i0] : 0;
const PxU32 Ref1 = dFaces ? dFaces[i1] : wFaces ? wFaces[i1] : 1;
const PxU32 Ref2 = dFaces ? dFaces[i2] : wFaces ? wFaces[i2] : 2;
FNormals[i] = (verts[Ref2]-verts[Ref0]).cross(verts[Ref1] - verts[Ref0]);
PX_ASSERT(!FNormals[i].isZero());
FNormals[i].normalize();
}
// Compute vertex normals
PxMemSet(normals, 0, nbVerts*sizeof(PxVec3));
// TTP 3751
PxVec3* TmpNormals = reinterpret_cast<PxVec3*>(PX_ALLOC_TEMP(sizeof(PxVec3)*nbVerts, "PxVec3"));
PxMemSet(TmpNormals, 0, nbVerts*sizeof(PxVec3));
for(PxU32 i=0;i<nbTris;i++)
{
PxU32 Ref[3];
Ref[0] = dFaces ? dFaces[i*3+0] : wFaces ? wFaces[i*3+0] : 0;
Ref[1] = dFaces ? dFaces[i*3+1] : wFaces ? wFaces[i*3+1] : 1;
Ref[2] = dFaces ? dFaces[i*3+2] : wFaces ? wFaces[i*3+2] : 2;
for(PxU32 j=0;j<3;j++)
{
if(TmpNormals[Ref[j]].isZero())
TmpNormals[Ref[j]] = FNormals[i];
}
}
//~TTP 3751
for(PxU32 i=0;i<nbTris;i++)
{
PxU32 Ref[3];
Ref[0] = dFaces ? dFaces[i*3+0] : wFaces ? wFaces[i*3+0] : 0;
Ref[1] = dFaces ? dFaces[i*3+1] : wFaces ? wFaces[i*3+1] : 1;
Ref[2] = dFaces ? dFaces[i*3+2] : wFaces ? wFaces[i*3+2] : 2;
normals[Ref[0]] += FNormals[i] * computeAngle(verts, Ref, Ref[0]);
normals[Ref[1]] += FNormals[i] * computeAngle(verts, Ref, Ref[1]);
normals[Ref[2]] += FNormals[i] * computeAngle(verts, Ref, Ref[2]);
}
// Normalize vertex normals
for(PxU32 i=0;i<nbVerts;i++)
{
if(normals[i].isZero())
normals[i] = TmpNormals[i];
// PX_ASSERT(!normals[i].isZero());
normals[i].normalize();
}
PX_FREE_AND_RESET(TmpNormals); // TTP 3751
PX_FREE_AND_RESET(FNormals);
return true;
}

View File

@ -0,0 +1,239 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "ExtSphericalJoint.h"
#include "ExtConstraintHelper.h"
#include "CmConeLimitHelper.h"
#include "PxPhysics.h"
using namespace physx;
using namespace Ext;
using namespace shdfnd;
PxSphericalJoint* physx::PxSphericalJointCreate(PxPhysics& physics, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1)
{
PX_CHECK_AND_RETURN_NULL(localFrame0.isSane(), "PxSphericalJointCreate: local frame 0 is not a valid transform");
PX_CHECK_AND_RETURN_NULL(localFrame1.isSane(), "PxSphericalJointCreate: local frame 1 is not a valid transform");
PX_CHECK_AND_RETURN_NULL(actor0 != actor1, "PxSphericalJointCreate: actors must be different");
PX_CHECK_AND_RETURN_NULL((actor0 && actor0->is<PxRigidBody>()) || (actor1 && actor1->is<PxRigidBody>()), "PxSphericalJointCreate: at least one actor must be dynamic");
SphericalJoint* j;
PX_NEW_SERIALIZED(j, SphericalJoint)(physics.getTolerancesScale(), actor0, localFrame0, actor1, localFrame1);
if(j->attach(physics, actor0, actor1))
return j;
PX_DELETE(j);
return NULL;
}
void SphericalJoint::setProjectionLinearTolerance(PxReal tolerance)
{
PX_CHECK_AND_RETURN(PxIsFinite(tolerance) && tolerance >=0, "PxSphericalJoint::setProjectionLinearTolerance: invalid parameter");
data().projectionLinearTolerance = tolerance;
markDirty();
}
PxReal SphericalJoint::getProjectionLinearTolerance() const
{
return data().projectionLinearTolerance;
}
void SphericalJoint::setLimitCone(const PxJointLimitCone &limit)
{
PX_CHECK_AND_RETURN(limit.isValid(), "PxSphericalJoint::setLimit: invalid parameter");
data().limit = limit;
markDirty();
}
PxJointLimitCone SphericalJoint::getLimitCone() const
{
return data().limit;
}
PxSphericalJointFlags SphericalJoint::getSphericalJointFlags(void) const
{
return data().jointFlags;
}
void SphericalJoint::setSphericalJointFlags(PxSphericalJointFlags flags)
{
data().jointFlags = flags;
}
void SphericalJoint::setSphericalJointFlag(PxSphericalJointFlag::Enum flag, bool value)
{
if(value)
data().jointFlags |= flag;
else
data().jointFlags &= ~flag;
markDirty();
}
PxReal SphericalJoint::getSwingYAngle() const
{
return getSwingYAngle_Internal();
}
PxReal SphericalJoint::getSwingZAngle() const
{
return getSwingZAngle_Internal();
}
bool SphericalJoint::attach(PxPhysics &physics, PxRigidActor* actor0, PxRigidActor* actor1)
{
mPxConstraint = physics.createConstraint(actor0, actor1, *this, sShaders, sizeof(SphericalJointData));
return mPxConstraint!=NULL;
}
void SphericalJoint::exportExtraData(PxSerializationContext& stream)
{
if(mData)
{
stream.alignData(PX_SERIAL_ALIGN);
stream.writeData(mData, sizeof(SphericalJointData));
}
stream.writeName(mName);
}
void SphericalJoint::importExtraData(PxDeserializationContext& context)
{
if(mData)
mData = context.readExtraData<SphericalJointData, PX_SERIAL_ALIGN>();
context.readName(mName);
}
void SphericalJoint::resolveReferences(PxDeserializationContext& context)
{
setPxConstraint(resolveConstraintPtr(context, getPxConstraint(), getConnector(), sShaders));
}
SphericalJoint* SphericalJoint::createObject(PxU8*& address, PxDeserializationContext& context)
{
SphericalJoint* obj = new (address) SphericalJoint(PxBaseFlag::eIS_RELEASABLE);
address += sizeof(SphericalJoint);
obj->importExtraData(context);
obj->resolveReferences(context);
return obj;
}
// global function to share the joint shaders with API capture
const PxConstraintShaderTable* Ext::GetSphericalJointShaderTable()
{
return &SphericalJoint::getConstraintShaderTable();
}
//~PX_SERIALIZATION
static void SphericalJointProject(const void* constantBlock, PxTransform& bodyAToWorld, PxTransform& bodyBToWorld, bool projectToA)
{
const SphericalJointData& data = *reinterpret_cast<const SphericalJointData*>(constantBlock);
PxTransform cA2w, cB2w, cB2cA, projected;
joint::computeDerived(data, bodyAToWorld, bodyBToWorld, cA2w, cB2w, cB2cA);
bool linearTrunc;
projected.p = joint::truncateLinear(cB2cA.p, data.projectionLinearTolerance, linearTrunc);
if(linearTrunc)
{
projected.q = cB2cA.q;
joint::projectTransforms(bodyAToWorld, bodyBToWorld, cA2w, cB2w, projected, data, projectToA);
}
}
static void SphericalJointVisualize(PxConstraintVisualizer& viz, const void* constantBlock, const PxTransform& body0Transform, const PxTransform& body1Transform, PxU32 flags)
{
const SphericalJointData& data = *reinterpret_cast<const SphericalJointData*>(constantBlock);
PxTransform cA2w, cB2w;
joint::computeJointFrames(cA2w, cB2w, data, body0Transform, body1Transform);
if(flags & PxConstraintVisualizationFlag::eLOCAL_FRAMES)
viz.visualizeJointFrames(cA2w, cB2w);
if((flags & PxConstraintVisualizationFlag::eLIMITS) && (data.jointFlags & PxSphericalJointFlag::eLIMIT_ENABLED))
{
if(cA2w.q.dot(cB2w.q)<0.0f)
cB2w.q = -cB2w.q;
const PxTransform cB2cA = cA2w.transformInv(cB2w);
PxQuat swing, twist;
Ps::separateSwingTwist(cB2cA.q,swing,twist);
// PT: TODO: refactor with D6 joint code
const PxReal pad = data.limit.isSoft() ? 0.0f : data.limit.contactDistance;
const PxVec3 swingAngle(0.0f, computeSwingAngle(swing.y, swing.w), computeSwingAngle(swing.z, swing.w));
Cm::ConeLimitHelperTanLess coneHelper(data.limit.yAngle, data.limit.zAngle, pad);
viz.visualizeLimitCone(cA2w, PxTan(data.limit.zAngle/4), PxTan(data.limit.yAngle/4), !coneHelper.contains(swingAngle));
}
}
static PxU32 SphericalJointSolverPrep(Px1DConstraint* constraints,
PxVec3& body0WorldOffset,
PxU32 /*maxConstraints*/,
PxConstraintInvMassScale& invMassScale,
const void* constantBlock,
const PxTransform& bA2w,
const PxTransform& bB2w,
bool /*useExtendedLimits*/,
PxVec3& cA2wOut, PxVec3& cB2wOut)
{
const SphericalJointData& data = *reinterpret_cast<const SphericalJointData*>(constantBlock);
PxTransform cA2w, cB2w;
joint::ConstraintHelper ch(constraints, invMassScale, cA2w, cB2w, body0WorldOffset, data, bA2w, bB2w);
if(cB2w.q.dot(cA2w.q)<0.0f)
cB2w.q = -cB2w.q;
if(data.jointFlags & PxSphericalJointFlag::eLIMIT_ENABLED)
{
PxQuat swing, twist;
Ps::separateSwingTwist(cA2w.q.getConjugate() * cB2w.q, swing, twist);
PX_ASSERT(PxAbs(swing.x)<1e-6f);
// PT: TODO: refactor with D6 joint code
PxVec3 axis;
PxReal error;
const PxReal pad = data.limit.isSoft() ? 0.0f : data.limit.contactDistance;
const Cm::ConeLimitHelperTanLess coneHelper(data.limit.yAngle, data.limit.zAngle, pad);
const bool active = coneHelper.getLimit(swing, axis, error);
if(active)
ch.angularLimit(cA2w.rotate(axis), error, data.limit);
}
PxVec3 ra, rb;
ch.prepareLockedAxes(cA2w.q, cB2w.q, cA2w.transformInv(cB2w.p), 7, 0, ra, rb);
cA2wOut = ra + bA2w.p;
cB2wOut = rb + bB2w.p;
return ch.getCount();
}
PxConstraintShaderTable Ext::SphericalJoint::sShaders = { SphericalJointSolverPrep, SphericalJointProject, SphericalJointVisualize, PxConstraintFlag::Enum(0) };

View File

@ -0,0 +1,130 @@
//
// 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-2021 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 NP_SPHERICALJOINTCONSTRAINT_H
#define NP_SPHERICALJOINTCONSTRAINT_H
#include "extensions/PxSphericalJoint.h"
#include "ExtJoint.h"
#include "CmUtils.h"
namespace physx
{
struct PxSphericalJointGeneratedValues;
namespace Ext
{
struct SphericalJointData: public JointData
{
//= 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.
//==================================================================================================
PxJointLimitCone limit;
PxReal projectionLinearTolerance;
PxSphericalJointFlags jointFlags;
// forestall compiler complaints about not being able to generate a constructor
private:
SphericalJointData(const PxJointLimitCone &cone):
limit(cone) {}
};
typedef Joint<PxSphericalJoint, PxSphericalJointGeneratedValues> SphericalJointT;
class SphericalJoint : public SphericalJointT
{
//= 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:
// PX_SERIALIZATION
SphericalJoint(PxBaseFlags baseFlags) : SphericalJointT(baseFlags) {}
virtual void exportExtraData(PxSerializationContext& context);
void importExtraData(PxDeserializationContext& context);
void resolveReferences(PxDeserializationContext& context);
static SphericalJoint* createObject(PxU8*& address, PxDeserializationContext& context);
static void getBinaryMetaData(PxOutputStream& stream);
//~PX_SERIALIZATION
SphericalJoint(const PxTolerancesScale& /*scale*/, PxRigidActor* actor0, const PxTransform& localFrame0, PxRigidActor* actor1, const PxTransform& localFrame1) :
SphericalJointT(PxJointConcreteType::eSPHERICAL, PxBaseFlag::eOWNS_MEMORY | PxBaseFlag::eIS_RELEASABLE, actor0, localFrame0, actor1, localFrame1, sizeof(SphericalJointData), "SphericalJointData")
{
SphericalJointData* data = static_cast<SphericalJointData*>(mData);
data->projectionLinearTolerance = 1e10f;
data->limit = PxJointLimitCone(PxPi/2, PxPi/2);
data->jointFlags = PxSphericalJointFlags();
}
// PxSphericalJoint
virtual void setLimitCone(const PxJointLimitCone &limit);
virtual PxJointLimitCone getLimitCone() const;
virtual void setSphericalJointFlags(PxSphericalJointFlags flags);
virtual void setSphericalJointFlag(PxSphericalJointFlag::Enum flag, bool value);
virtual PxSphericalJointFlags getSphericalJointFlags(void) const;
virtual void setProjectionLinearTolerance(PxReal distance);
virtual PxReal getProjectionLinearTolerance() const;
virtual PxReal getSwingYAngle() const;
virtual PxReal getSwingZAngle() const;
//~PxSphericalJoint
bool attach(PxPhysics &physics, PxRigidActor* actor0, PxRigidActor* actor1);
static const PxConstraintShaderTable& getConstraintShaderTable() { return sShaders; }
virtual PxConstraintSolverPrep getPrep() const { return sShaders.solverPrep; }
private:
static PxConstraintShaderTable sShaders;
PX_FORCE_INLINE SphericalJointData& data() const
{
return *static_cast<SphericalJointData*>(mData);
}
};
} // namespace Ext
namespace Ext
{
// global function to share the joint shaders with API capture
extern "C" const PxConstraintShaderTable* GetSphericalJointShaderTable();
}
}
#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-2021 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_NP_TASK_QUEUE_HELPER_H
#define PX_PHYSICS_EXTENSIONS_NP_TASK_QUEUE_HELPER_H
#include "task/PxTask.h"
#include "CmPhysXCommon.h"
#include "ExtSharedQueueEntryPool.h"
namespace physx
{
#define EXT_TASK_QUEUE_ENTRY_POOL_SIZE 128
namespace Ext
{
class TaskQueueHelper
{
public:
static PxBaseTask* fetchTask(Ps::SList& taskQueue, Ext::SharedQueueEntryPool<>& entryPool)
{
SharedQueueEntry* entry = static_cast<SharedQueueEntry*>(taskQueue.pop());
if (entry)
{
PxBaseTask* task = reinterpret_cast<PxBaseTask*>(entry->mObjectRef);
entryPool.putEntry(*entry);
return task;
}
else
return NULL;
}
};
} // namespace Ext
}
#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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "geometry/PxMeshQuery.h"
#include "geometry/PxGeometryQuery.h"
#include "geometry/PxTriangleMeshGeometry.h"
#include "geometry/PxHeightFieldGeometry.h"
#include "geometry/PxHeightField.h"
#include "geometry/PxTriangleMesh.h"
#include "extensions/PxTriangleMeshExt.h"
#include "PsAllocator.h"
using namespace physx;
PxMeshOverlapUtil::PxMeshOverlapUtil() : mResultsMemory(mResults), mNbResults(0), mMaxNbResults(256)
{
}
PxMeshOverlapUtil::~PxMeshOverlapUtil()
{
if(mResultsMemory != mResults)
PX_FREE(mResultsMemory);
}
PxU32 PxMeshOverlapUtil::findOverlap(const PxGeometry& geom, const PxTransform& geomPose, const PxTriangleMeshGeometry& meshGeom, const PxTransform& meshPose)
{
bool overflow;
PxU32 nbTouchedTris = PxMeshQuery::findOverlapTriangleMesh(geom, geomPose, meshGeom, meshPose, mResultsMemory, mMaxNbResults, 0, overflow);
if(overflow)
{
const PxU32 maxNbTris = meshGeom.triangleMesh->getNbTriangles();
if(!maxNbTris)
{
mNbResults = 0;
return 0;
}
if(mMaxNbResults<maxNbTris)
{
if(mResultsMemory != mResults)
PX_FREE(mResultsMemory);
mResultsMemory = reinterpret_cast<PxU32*>(PX_ALLOC(sizeof(PxU32)*maxNbTris, "PxMeshOverlapUtil::findOverlap"));
mMaxNbResults = maxNbTris;
}
nbTouchedTris = PxMeshQuery::findOverlapTriangleMesh(geom, geomPose, meshGeom, meshPose, mResultsMemory, mMaxNbResults, 0, overflow);
PX_ASSERT(nbTouchedTris);
PX_ASSERT(!overflow);
}
mNbResults = nbTouchedTris;
return nbTouchedTris;
}
PxU32 PxMeshOverlapUtil::findOverlap(const PxGeometry& geom, const PxTransform& geomPose, const PxHeightFieldGeometry& hfGeom, const PxTransform& hfPose)
{
bool overflow = true;
PxU32 nbTouchedTris = PxMeshQuery::findOverlapHeightField(geom, geomPose, hfGeom, hfPose, mResultsMemory, mMaxNbResults, 0, overflow);
if(overflow)
{
const PxU32 maxNbTris = hfGeom.heightField->getNbRows()*hfGeom.heightField->getNbColumns()*2;
if(!maxNbTris)
{
mNbResults = 0;
return 0;
}
if(mMaxNbResults<maxNbTris)
{
if(mResultsMemory != mResults)
PX_FREE(mResultsMemory);
mResultsMemory = reinterpret_cast<PxU32*>(PX_ALLOC(sizeof(PxU32)*maxNbTris, "PxMeshOverlapUtil::findOverlap"));
mMaxNbResults = maxNbTris;
}
nbTouchedTris = PxMeshQuery::findOverlapHeightField(geom, geomPose, hfGeom, hfPose, mResultsMemory, mMaxNbResults, 0, overflow);
PX_ASSERT(nbTouchedTris);
PX_ASSERT(!overflow);
}
mNbResults = nbTouchedTris;
return nbTouchedTris;
}
namespace
{
template<typename MeshGeometry>
bool computeMeshPenetrationT(PxVec3& direction,
PxReal& depth,
const PxGeometry& geom,
const PxTransform& geomPose,
const MeshGeometry& meshGeom,
const PxTransform& meshPose,
PxU32 maxIter,
PxU32* nbIterOut)
{
PxU32 nbIter = 0;
PxTransform pose = geomPose;
for (; nbIter < maxIter; nbIter++)
{
PxVec3 currentDir;
PxF32 currentDepth;
if (!PxGeometryQuery::computePenetration(currentDir, currentDepth, geom, pose, meshGeom, meshPose))
break;
pose.p += currentDir * currentDepth;
}
if(nbIterOut)
*nbIterOut = nbIter;
PxVec3 diff = pose.p - geomPose.p;
depth = diff.magnitude();
if (depth>0)
direction = diff / depth;
return nbIter!=0;
}
}
bool physx::PxComputeTriangleMeshPenetration(PxVec3& direction,
PxReal& depth,
const PxGeometry& geom,
const PxTransform& geomPose,
const PxTriangleMeshGeometry& meshGeom,
const PxTransform& meshPose,
PxU32 maxIter,
PxU32* nbIter)
{
return computeMeshPenetrationT(direction, depth, geom, geomPose, meshGeom, meshPose, maxIter, nbIter);
}
bool physx::PxComputeHeightFieldPenetration(PxVec3& direction,
PxReal& depth,
const PxGeometry& geom,
const PxTransform& geomPose,
const PxHeightFieldGeometry& hfGeom,
const PxTransform& meshPose,
PxU32 maxIter,
PxU32* nbIter)
{
return computeMeshPenetrationT(direction, depth, geom, geomPose, hfGeom, meshPose, maxIter, nbIter);
}

View File

@ -0,0 +1,306 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "common/PxSerializer.h"
#include "extensions/PxSerialization.h"
#include "PxPhysics.h"
#include "PxPhysicsSerialization.h"
#include "PsHash.h"
#include "PsHashMap.h"
#include "PsFoundation.h"
#include "PsString.h"
#include "SnFile.h"
#include "SnSerializationContext.h"
#include "SnConvX_Align.h"
#include "serialization/SnSerializationRegistry.h"
#include "serialization/SnSerialUtils.h"
#include "CmIO.h"
#include "CmCollection.h"
using namespace physx;
using namespace Sn;
namespace
{
PX_INLINE PxU8* alignPtr(PxU8* ptr, PxU32 alignment = PX_SERIAL_ALIGN)
{
if(!alignment)
return ptr;
const PxU32 padding = getPadding(size_t(ptr), alignment);
PX_ASSERT(!getPadding(size_t(ptr + padding), alignment));
return ptr + padding;
}
PX_FORCE_INLINE PxU32 read32(PxU8*& address)
{
const PxU32 value = *reinterpret_cast<PxU32*>(address);
address += sizeof(PxU32);
return value;
}
bool readHeader(PxU8*& address)
{
const PxU32 header = read32(address);
PX_UNUSED(header);
const PxU32 version = read32(address);
PX_UNUSED(version);
char binaryVersionGuid[SN_BINARY_VERSION_GUID_NUM_CHARS + 1];
PxMemCopy(binaryVersionGuid, address, SN_BINARY_VERSION_GUID_NUM_CHARS);
binaryVersionGuid[SN_BINARY_VERSION_GUID_NUM_CHARS] = 0;
address += SN_BINARY_VERSION_GUID_NUM_CHARS;
PX_UNUSED(binaryVersionGuid);
const PxU32 platformTag = read32(address);
PX_UNUSED(platformTag);
const PxU32 markedPadding = read32(address);
PX_UNUSED(markedPadding);
#if PX_CHECKED
if (header != PX_MAKE_FOURCC('S','E','B','D'))
{
Ps::getFoundation().error(physx::PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"Buffer contains data with wrong header indicating invalid binary data.");
return false;
}
if (!checkCompatibility(binaryVersionGuid))
{
Ps::getFoundation().error(physx::PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"Buffer contains binary data version 0x%s and is incompatible with this PhysX sdk (0x%s).\n",
binaryVersionGuid, getBinaryVersionGuid());
return false;
}
if (platformTag != getBinaryPlatformTag())
{
Ps::getFoundation().error(physx::PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"Buffer contains data with platform mismatch:\nExpected: %s \nActual: %s\n",
getBinaryPlatformName(getBinaryPlatformTag()),
getBinaryPlatformName(platformTag));
return false;
}
#endif
return true;
}
bool checkImportReferences(const ImportReference* importReferences, PxU32 nbImportReferences, const Cm::Collection* externalRefs)
{
if (!externalRefs)
{
if (nbImportReferences > 0)
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__, "PxSerialization::createCollectionFromBinary: External references needed but no externalRefs collection specified.");
return false;
}
}
else
{
for (PxU32 i=0; i<nbImportReferences;i++)
{
PxSerialObjectId id = importReferences[i].id;
PxType type = importReferences[i].type;
PxBase* referencedObject = externalRefs->find(id);
if (!referencedObject)
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__, "PxSerialization::createCollectionFromBinary: External reference %" PX_PRIu64 " expected in externalRefs collection but not found.", id);
return false;
}
if (referencedObject->getConcreteType() != type)
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__, "PxSerialization::createCollectionFromBinary: External reference %d type mismatch. Expected %d but found %d in externalRefs collection.", type, referencedObject->getConcreteType());
return false;
}
}
}
return true;
}
}
PxCollection* PxSerialization::createCollectionFromBinary(void* memBlock, PxSerializationRegistry& sr, const PxCollection* pxExternalRefs)
{
#if PX_CHECKED
if(size_t(memBlock) & (PX_SERIAL_FILE_ALIGN-1))
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__, "Buffer must be 128-bytes aligned.");
return NULL;
}
#endif
PxU8* address = reinterpret_cast<PxU8*>(memBlock);
const Cm::Collection* externalRefs = static_cast<const Cm::Collection*>(pxExternalRefs);
if (!readHeader(address))
{
return NULL;
}
ManifestEntry* manifestTable;
PxU32 nbObjectsInCollection;
PxU32 objectDataEndOffset;
// read number of objects in collection
address = alignPtr(address);
nbObjectsInCollection = read32(address);
// read manifest (PxU32 offset, PxConcreteType type)
{
address = alignPtr(address);
PxU32 nbManifestEntries = read32(address);
PX_ASSERT(*reinterpret_cast<PxU32*>(address) == 0); //first offset is always 0
manifestTable = (nbManifestEntries > 0) ? reinterpret_cast<ManifestEntry*>(address) : NULL;
address += nbManifestEntries*sizeof(ManifestEntry);
objectDataEndOffset = read32(address);
}
ImportReference* importReferences;
PxU32 nbImportReferences;
// read import references
{
address = alignPtr(address);
nbImportReferences = read32(address);
importReferences = (nbImportReferences > 0) ? reinterpret_cast<ImportReference*>(address) : NULL;
address += nbImportReferences*sizeof(ImportReference);
}
if (!checkImportReferences(importReferences, nbImportReferences, externalRefs))
{
return NULL;
}
ExportReference* exportReferences;
PxU32 nbExportReferences;
// read export references
{
address = alignPtr(address);
nbExportReferences = read32(address);
exportReferences = (nbExportReferences > 0) ? reinterpret_cast<ExportReference*>(address) : NULL;
address += nbExportReferences*sizeof(ExportReference);
}
// read internal references arrays
PxU32 nbInternalPtrReferences = 0;
PxU32 nbInternalHandle16References = 0;
InternalReferencePtr* internalPtrReferences = NULL;
InternalReferenceHandle16* internalHandle16References = NULL;
{
address = alignPtr(address);
nbInternalPtrReferences = read32(address);
internalPtrReferences = (nbInternalPtrReferences > 0) ? reinterpret_cast<InternalReferencePtr*>(address) : NULL;
address += nbInternalPtrReferences*sizeof(InternalReferencePtr);
nbInternalHandle16References = read32(address);
internalHandle16References = (nbInternalHandle16References > 0) ? reinterpret_cast<InternalReferenceHandle16*>(address) : NULL;
address += nbInternalHandle16References*sizeof(InternalReferenceHandle16);
}
// create internal references map
InternalPtrRefMap internalPtrReferencesMap(nbInternalPtrReferences*2);
{
//create hash (we should load the hashes directly from memory)
for (PxU32 i = 0; i < nbInternalPtrReferences; i++)
{
const InternalReferencePtr& ref = internalPtrReferences[i];
internalPtrReferencesMap.insertUnique(ref.reference, SerialObjectIndex(ref.objIndex));
}
}
InternalHandle16RefMap internalHandle16ReferencesMap(nbInternalHandle16References*2);
{
for (PxU32 i=0;i<nbInternalHandle16References;i++)
{
const InternalReferenceHandle16& ref = internalHandle16References[i];
internalHandle16ReferencesMap.insertUnique(ref.reference, SerialObjectIndex(ref.objIndex));
}
}
SerializationRegistry& sn = static_cast<SerializationRegistry&>(sr);
Cm::Collection* collection = static_cast<Cm::Collection*>(PxCreateCollection());
PX_ASSERT(collection);
collection->mObjects.reserve(nbObjectsInCollection*2);
if(nbExportReferences > 0)
collection->mIds.reserve(nbExportReferences*2);
PxU8* addressObjectData = alignPtr(address);
PxU8* addressExtraData = alignPtr(addressObjectData + objectDataEndOffset);
DeserializationContext context(manifestTable, importReferences, addressObjectData, internalPtrReferencesMap, internalHandle16ReferencesMap, externalRefs, addressExtraData);
// iterate over memory containing PxBase objects, create the instances, resolve the addresses, import the external data, add to collection.
{
PxU32 nbObjects = nbObjectsInCollection;
while(nbObjects--)
{
address = alignPtr(address);
context.alignExtraData();
// read PxBase header with type and get corresponding serializer.
PxBase* header = reinterpret_cast<PxBase*>(address);
const PxType classType = header->getConcreteType();
const PxSerializer* serializer = sn.getSerializer(classType);
PX_ASSERT(serializer);
PxBase* instance = serializer->createObject(address, context);
if (!instance)
{
Ps::getFoundation().error(physx::PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"Cannot create class instance for concrete type %d.", classType);
collection->release();
return NULL;
}
collection->internalAdd(instance);
}
}
PX_ASSERT(nbObjectsInCollection == collection->internalGetNbObjects());
// update new collection with export references
{
PX_ASSERT(addressObjectData != NULL);
for (PxU32 i=0;i<nbExportReferences;i++)
{
bool isExternal;
PxU32 manifestIndex = exportReferences[i].objIndex.getIndex(isExternal);
PX_ASSERT(!isExternal);
PxBase* obj = reinterpret_cast<PxBase*>(addressObjectData + manifestTable[manifestIndex].offset);
collection->mIds.insertUnique(exportReferences[i].id, obj);
collection->mObjects[obj] = exportReferences[i].id;
}
}
PxAddCollectionToPhysics(*collection);
return collection;
}

View File

@ -0,0 +1,426 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "common/PxSerializer.h"
#include "extensions/PxSerialization.h"
#include "extensions/PxBinaryConverter.h"
#include "extensions/PxDefaultStreams.h"
#include "PxPhysicsVersion.h"
#include "PsHash.h"
#include "PsHashMap.h"
#include "PsUtilities.h"
#include "PsSort.h"
#include "PsString.h"
#include "PsIntrinsics.h"
#include "SnFile.h"
#include "SnSerializationContext.h"
#include "serialization/SnSerialUtils.h"
#include "serialization/SnSerializationRegistry.h"
#include "SnConvX_Align.h"
#include "CmIO.h"
#include "CmCollection.h"
using namespace physx;
using namespace Cm;
using namespace Sn;
//------------------------------------------------------------------------------------
//// Binary Serialized PxCollection, format documentation
//------------------------------------------------------------------------------------
//
//
//------------------------------------------------------------------------------------
//// overview:
//// header information
//// manifest table
//// import references
//// export references
//// internal references
//// object data
//// extra data
//------------------------------------------------------------------------------------
//
//
//------------------------------------------------------------------------------------
//// header information:
//// header tag plus various version and platform information
//------------------------------------------------------------------------------------
// header SEBD
// PX_PHYSICS_VERSION
// PX_BINARY_SERIAL_VERSION
// platform tag
// markedPadding (on for PX_CHECKED)
// nbObjectsInCollection
//
//
//------------------------------------------------------------------------------------
//// manifest table:
//// one entry per collected object
//// offsets relative to object data buffer
//------------------------------------------------------------------------------------
// alignment
// PxU32 size
// (PxU32 offset, PxType type)*size
// PxU32 endOffset
//
//
//------------------------------------------------------------------------------------
//// import references:
//// one entry per required reference to external collection
//------------------------------------------------------------------------------------
// alignment
// PxU32 size
// (PxSerialObjectId id, PxType type)*size
//
//
//------------------------------------------------------------------------------------
//// export references:
//// one entry per object in the collection with id
//// object indices point into the manifest table (objects in the same collection)
//------------------------------------------------------------------------------------
// alignment
// PxU32 size
// (PxSerialObjectId id, SerialObjectIndex objIndex)*size
//
//
//------------------------------------------------------------------------------------
//// internal references:
//// one entry per reference, kind pair
//// object indices point either into the manifest table or into the import references
//// depending on whether the entry references the same collection or the external one
//// one section for pointer type references and one for index type references.
//------------------------------------------------------------------------------------
// alignment
// PxU32 sizePtrs;
// (size_t reference, PxU32 kind, SerialObjectIndex objIndex)*sizePtrs
// PxU32 sizeHandle16;
// (PxU16 reference, PxU32 kind, SerialObjectIndex objIndex)*sizeHandle16
//
//
//------------------------------------------------------------------------------------
//// object data:
//// serialized PxBase derived class instances
//// each object size depends on specific class
//// offsets are stored in manifest table
//------------------------------------------------------------------------------------
// alignment
// (PxConcreteType type, -----)
// alignment
// (PxConcreteType type, --------)
// alignment
// (PxConcreteType type, --)
// .
// .
//
//
// -----------------------------------------------------------------------------------
//// extra data:
//// extra data memory block
//// serialized and deserialized by PxBase implementations
////----------------------------------------------------------------------------------
// extra data
//
//------------------------------------------------------------------------------------
namespace
{
class LegacySerialStream : public PxSerializationContext
{
public:
LegacySerialStream(OutputStreamWriter& writer,
const PxCollection& collection,
bool exportNames) : mWriter(writer), mCollection(collection), mExportNames(exportNames) {}
void writeData(const void* buffer, PxU32 size) { mWriter.write(buffer, size); }
PxU32 getTotalStoredSize() { return mWriter.getStoredSize(); }
void alignData(PxU32 alignment)
{
if(!alignment)
return;
PxI32 bytesToPad = PxI32(getPadding(getTotalStoredSize(), alignment));
static const PxI32 BUFSIZE = 64;
char buf[BUFSIZE];
PxMemSet(buf, 0, bytesToPad < BUFSIZE ? PxU32(bytesToPad) : PxU32(BUFSIZE));
while(bytesToPad > 0)
{
writeData(buf, bytesToPad < BUFSIZE ? PxU32(bytesToPad) : PxU32(BUFSIZE));
bytesToPad -= BUFSIZE;
}
PX_ASSERT(!getPadding(getTotalStoredSize(), alignment));
}
virtual void registerReference(PxBase&, PxU32, size_t)
{
Ps::getFoundation().error(physx::PxErrorCode::eINVALID_OPERATION, __FILE__, __LINE__,
"Cannot register references during exportData, exportExtraData.");
}
virtual const PxCollection& getCollection() const
{
return mCollection;
}
virtual void writeName(const char* name)
{
PxU32 len = name && mExportNames ? PxU32(strlen(name)) + 1 : 0;
writeData(&len, sizeof(len));
if(len) writeData(name, len);
}
private:
LegacySerialStream& operator=(const LegacySerialStream&);
OutputStreamWriter& mWriter;
const PxCollection& mCollection;
bool mExportNames;
};
void writeHeader(PxSerializationContext& stream, bool hasDeserializedAssets)
{
PX_UNUSED(hasDeserializedAssets);
//serialized binary data.
const PxU32 header = PX_MAKE_FOURCC('S','E','B','D');
stream.writeData(&header, sizeof(PxU32));
PxU32 version = PX_PHYSICS_VERSION;
stream.writeData(&version, sizeof(PxU32));
stream.writeData(PX_BINARY_SERIAL_VERSION, SN_BINARY_VERSION_GUID_NUM_CHARS);
PxU32 platformTag = getBinaryPlatformTag();
stream.writeData(&platformTag, sizeof(PxU32));
PxU32 markedPadding = 0;
#if PX_CHECKED
if(!hasDeserializedAssets)
markedPadding = 1;
#endif
stream.writeData(&markedPadding, sizeof(PxU32));
}
template<typename InternalReferenceType>
struct InternalReferencePredicate
{
PX_FORCE_INLINE bool operator()(InternalReferenceType& a, InternalReferenceType& b) const { return a.objIndex < b.objIndex; }
};
}
bool PxSerialization::serializeCollectionToBinary(PxOutputStream& outputStream, PxCollection& pxCollection, PxSerializationRegistry& sr, const PxCollection* pxExternalRefs, bool exportNames)
{
if(!PxSerialization::isSerializable(pxCollection, sr, pxExternalRefs))
return false;
Collection& collection = static_cast<Collection&>(pxCollection);
const Collection* externalRefs = static_cast<const Collection*>(pxExternalRefs);
//temporary memory stream which allows fixing up data up stream
SerializationRegistry& sn = static_cast<SerializationRegistry&>(sr);
// sort collection by "order" value (this will be the order in which they get serialized)
sortCollection(collection, sn, false);
//initialized the context with the sorted collection.
SerializationContext context(collection, externalRefs);
// gather reference information
bool hasDeserializedAssets = false;
{
const PxU32 nb = collection.internalGetNbObjects();
for(PxU32 i=0;i<nb;i++)
{
PxBase* s = collection.internalGetObject(i);
PX_ASSERT(s && s->getConcreteType());
#if PX_CHECKED
//can't guarantee marked padding for deserialized instances
if(!(s->getBaseFlags() & PxBaseFlag::eOWNS_MEMORY))
hasDeserializedAssets = true;
#endif
const PxSerializer* serializer = sn.getSerializer(s->getConcreteType());
PX_ASSERT(serializer);
serializer->registerReferences(*s, context);
}
}
// now start the actual serialization into the output stream
OutputStreamWriter writer(outputStream);
LegacySerialStream stream(writer, collection, exportNames);
writeHeader(stream, hasDeserializedAssets);
// write size of collection
stream.alignData(PX_SERIAL_ALIGN);
PxU32 nbObjectsInCollection = collection.internalGetNbObjects();
stream.writeData(&nbObjectsInCollection, sizeof(PxU32));
// write the manifest table (PxU32 offset, PxConcreteType type)
{
Ps::Array<ManifestEntry> manifestTable(collection.internalGetNbObjects());
PxU32 headerOffset = 0;
for(PxU32 i=0;i<collection.internalGetNbObjects();i++)
{
PxBase* s = collection.internalGetObject(i);
PX_ASSERT(s && s->getConcreteType());
PxType concreteType = s->getConcreteType();
const PxSerializer* serializer = sn.getSerializer(concreteType);
PX_ASSERT(serializer);
manifestTable[i] = ManifestEntry(headerOffset, concreteType);
PxU32 classSize = PxU32(serializer->getClassSize());
headerOffset += getPadding(classSize, PX_SERIAL_ALIGN) + classSize;
}
stream.alignData(PX_SERIAL_ALIGN);
const PxU32 nb = manifestTable.size();
stream.writeData(&nb, sizeof(PxU32));
stream.writeData(manifestTable.begin(), manifestTable.size()*sizeof(ManifestEntry));
//store offset for end of object buffer (PxU32 offset)
stream.writeData(&headerOffset, sizeof(PxU32));
}
// write import references
{
const Ps::Array<ImportReference>& importReferences = context.getImportReferences();
stream.alignData(PX_SERIAL_ALIGN);
const PxU32 nb = importReferences.size();
stream.writeData(&nb, sizeof(PxU32));
stream.writeData(importReferences.begin(), importReferences.size()*sizeof(ImportReference));
}
// write export references
{
PxU32 nbIds = collection.getNbIds();
Ps::Array<ExportReference> exportReferences(nbIds);
//we can't get quickly from id to object index in collection.
//if we only need this here, its not worth to build a hash
nbIds = 0;
for (PxU32 i=0;i<collection.getNbObjects();i++)
{
PxBase& obj = collection.getObject(i);
PxSerialObjectId id = collection.getId(obj);
if (id != PX_SERIAL_OBJECT_ID_INVALID)
{
SerialObjectIndex objIndex(i, false); //i corresponds to manifest entry
exportReferences[nbIds++] = ExportReference(id, objIndex);
}
}
stream.alignData(PX_SERIAL_ALIGN);
stream.writeData(&nbIds, sizeof(PxU32));
stream.writeData(exportReferences.begin(), exportReferences.size()*sizeof(ExportReference));
}
// write internal references
{
InternalPtrRefMap& internalPtrReferencesMap = context.getInternalPtrReferencesMap();
Ps::Array<InternalReferencePtr> internalReferencesPtr(internalPtrReferencesMap.size());
PxU32 nbInternalPtrReferences = 0;
InternalHandle16RefMap& internalHandle16ReferencesMap = context.getInternalHandle16ReferencesMap();
Ps::Array<InternalReferenceHandle16> internalReferencesHandle16(internalHandle16ReferencesMap.size());
PxU32 nbInternalHandle16References = 0;
{
for(InternalPtrRefMap::Iterator iter = internalPtrReferencesMap.getIterator(); !iter.done(); ++iter)
internalReferencesPtr[nbInternalPtrReferences++] = InternalReferencePtr(iter->first, iter->second);
for(InternalHandle16RefMap::Iterator iter = internalHandle16ReferencesMap.getIterator(); !iter.done(); ++iter)
internalReferencesHandle16[nbInternalHandle16References++] = InternalReferenceHandle16(Ps::to16(iter->first), iter->second);
//sort InternalReferences according to SerialObjectIndex for determinism
Ps::sort<InternalReferencePtr, InternalReferencePredicate<InternalReferencePtr> >(internalReferencesPtr.begin(), internalReferencesPtr.size(), InternalReferencePredicate<InternalReferencePtr>());
Ps::sort<InternalReferenceHandle16, InternalReferencePredicate<InternalReferenceHandle16> >(internalReferencesHandle16.begin(), internalReferencesHandle16.size(), InternalReferencePredicate<InternalReferenceHandle16>());
}
stream.alignData(PX_SERIAL_ALIGN);
stream.writeData(&nbInternalPtrReferences, sizeof(PxU32));
stream.writeData(internalReferencesPtr.begin(), internalReferencesPtr.size()*sizeof(InternalReferencePtr));
stream.writeData(&nbInternalHandle16References, sizeof(PxU32));
stream.writeData(internalReferencesHandle16.begin(), internalReferencesHandle16.size()*sizeof(InternalReferenceHandle16));
}
// write object data
{
stream.alignData(PX_SERIAL_ALIGN);
const PxU32 nb = collection.internalGetNbObjects();
for(PxU32 i=0;i<nb;i++)
{
PxBase* s = collection.internalGetObject(i);
PX_ASSERT(s && s->getConcreteType());
const PxSerializer* serializer = sn.getSerializer(s->getConcreteType());
PX_ASSERT(serializer);
stream.alignData(PX_SERIAL_ALIGN);
serializer->exportData(*s, stream);
}
}
// write extra data
{
const PxU32 nb = collection.internalGetNbObjects();
for(PxU32 i=0;i<nb;i++)
{
PxBase* s = collection.internalGetObject(i);
PX_ASSERT(s && s->getConcreteType());
const PxSerializer* serializer = sn.getSerializer(s->getConcreteType());
PX_ASSERT(serializer);
stream.alignData(PX_SERIAL_ALIGN);
serializer->exportExtraData(*s, stream);
}
}
return true;
}
bool PxSerialization::serializeCollectionToBinaryDeterministic(PxOutputStream& outputStream, PxCollection& pxCollection, PxSerializationRegistry& sr, const PxCollection* pxExternalRefs, bool exportNames)
{
PxDefaultMemoryOutputStream tmpOutputStream;
if (!serializeCollectionToBinary(tmpOutputStream, pxCollection, sr, pxExternalRefs, exportNames))
return false;
PxDefaultMemoryOutputStream metaDataOutput;
dumpBinaryMetaData(metaDataOutput, sr);
PxBinaryConverter* converter = createBinaryConverter();
PxDefaultMemoryInputData srcMetaData(metaDataOutput.getData(), metaDataOutput.getSize());
PxDefaultMemoryInputData dstMetaData(metaDataOutput.getData(), metaDataOutput.getSize());
if (!converter->setMetaData(srcMetaData, dstMetaData))
return false;
PxDefaultMemoryInputData srcBinaryData(tmpOutputStream.getData(), tmpOutputStream.getSize());
bool ret = converter->convert(srcBinaryData, srcBinaryData.getLength(), outputStream);
converter->release();
return ret;
}

View File

@ -0,0 +1,166 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
/*
- get rid of STL
- NpArticulationLinkArray with more than 4 entries
- big convexes Xbox => PC
- put a cache in "convertClass" function
- remove MD one at a time and check what happens in the converter. Make it robust/report errors
- for xbox, compare against source xbox file if it exists
- maybe put some info in the header to display "File generated by ConvX 1.xx" on screen (to debug)
- report inconsistent naming convention in each class!!!!
- try to automatically discover padding bytes? use "0xcd" pattern?
* do last param of XXXX_ITEMS macro automatically
- what if source files are 64bits? can we safely convert a 64bit ptr to 32bit?
*/
#include "foundation/PxErrorCallback.h"
#include "foundation/PxAllocatorCallback.h"
#include "foundation/PxIO.h"
#include "SnConvX.h"
#include "serialization/SnSerializationRegistry.h"
#include <assert.h>
#include "PsFoundation.h"
using namespace physx;
Sn::ConvX::ConvX() :
mMetaData_Src (NULL),
mMetaData_Dst (NULL),
mOutStream (NULL),
mMustFlip (false),
mOutputSize (0),
mSrcPtrSize (0),
mDstPtrSize (0),
mNullPtr (false),
mNoOutput (false),
mMarkedPadding (false),
mNbErrors (0),
mNbWarnings (0),
mReportMode (PxConverterReportMode::eNORMAL),
mPerformConversion (true)
{
// memset(mZeros, 0, CONVX_ZERO_BUFFER_SIZE);
memset(mZeros, 0x42, CONVX_ZERO_BUFFER_SIZE);
}
Sn::ConvX::~ConvX()
{
resetNbErrors();
resetConvexFlags();
releaseMetaData();
resetUnions();
}
void Sn::ConvX::release()
{
delete this;
}
bool Sn::ConvX::setMetaData(PxInputStream& inputStream, MetaDataType type)
{
resetNbErrors();
return (loadMetaData(inputStream, type) != NULL);
}
bool Sn::ConvX::setMetaData(PxInputStream& srcMetaData, PxInputStream& dstMetaData)
{
releaseMetaData();
resetUnions();
if(!setMetaData(srcMetaData, META_DATA_SRC))
return false;
if(!setMetaData(dstMetaData, META_DATA_DST))
return false;
return true;
}
bool Sn::ConvX::compareMetaData() const
{
if (!mMetaData_Src || !mMetaData_Dst) {
Ps::getFoundation().error(PxErrorCode::eINVALID_OPERATION, __FILE__, __LINE__,
"PxBinaryConverter: metadata not defined. Call PxBinaryConverter::setMetaData first.\n");
return false;
}
return mMetaData_Src->compare(*mMetaData_Dst);
}
bool Sn::ConvX::convert(PxInputStream& srcStream, PxU32 srcSize, PxOutputStream& targetStream)
{
if(!mMetaData_Src || !mMetaData_Dst)
{
Ps::getFoundation().error(PxErrorCode::eINVALID_OPERATION, __FILE__, __LINE__,
"PxBinaryConverter: metadata not defined. Call PxBinaryConverter::setMetaData first.\n");
return false;
}
resetConvexFlags();
resetNbErrors();
bool conversionStatus = false;
if(mPerformConversion)
{
if(srcSize == 0)
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"PxBinaryConverter: source serialized data size is zero.\n");
return false;
}
void* memory = PX_ALLOC_TEMP(srcSize+ALIGN_FILE, "ConvX source file");
void* memoryA = reinterpret_cast<void*>((size_t(memory) + ALIGN_FILE)&~(ALIGN_FILE-1));
const PxU32 nbBytesRead = srcStream.read(memoryA, srcSize);
if(nbBytesRead != srcSize)
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"PxBinaryConverter: failure on reading source serialized data.\n");
PX_FREE(memory);
return false;
}
displayMessage(PxErrorCode::eDEBUG_INFO, "\n\nConverting...\n\n");
{
if(!initOutput(targetStream))
{
PX_FREE(memory);
return false;
}
conversionStatus = convert(memoryA, int(srcSize));
closeOutput();
}
PX_FREE(memory);
}
return conversionStatus;
}

View File

@ -0,0 +1,196 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
#ifndef PX_CONVX_H
#define PX_CONVX_H
#include "foundation/PxErrors.h"
#include "common/PxTypeInfo.h"
#include "extensions/PxBinaryConverter.h"
#include "CmPhysXCommon.h"
#include "PsUserAllocated.h"
#include "PsHashMap.h"
#include "SnConvX_Common.h"
#include "SnConvX_Union.h"
#include "SnConvX_MetaData.h"
#include "SnConvX_Align.h"
#define CONVX_ZERO_BUFFER_SIZE 256
namespace physx {
class PxSerializationRegistry;
namespace Sn {
struct HeightFieldData;
class PointerRemap
{
public:
PointerRemap();
~PointerRemap();
void setObjectRef(PxU64 object64, PxU32 ref);
bool getObjectRef(PxU64 object64, PxU32& ref) const;
typedef Ps::HashMap<PxU64, PxU32> PointerMap;
PointerMap mData;
};
class Handle16Remap
{
public:
Handle16Remap();
~Handle16Remap();
void setObjectRef(PxU16 object, PxU16 ref);
bool getObjectRef(PxU16 object, PxU16& ref) const;
typedef Ps::HashMap<PxU16, PxU16> Handle16Map;
Handle16Map mData;
};
class ConvX : public physx::PxBinaryConverter, public shdfnd::UserAllocated
{
public:
ConvX();
virtual ~ConvX();
virtual void release();
virtual void setReportMode(PxConverterReportMode::Enum mode) { mReportMode = mode; }
PX_FORCE_INLINE bool silentMode() const { return mReportMode==PxConverterReportMode::eNONE; }
PX_FORCE_INLINE bool verboseMode() const { return mReportMode==PxConverterReportMode::eVERBOSE; }
virtual bool setMetaData(PxInputStream& srcMetaData, PxInputStream& dstMetaData);
virtual bool compareMetaData() const;
virtual bool convert(PxInputStream& srcStream, PxU32 srcSize, PxOutputStream& targetStream);
private:
ConvX& operator=(const ConvX&);
bool setMetaData(PxInputStream& inputStream, MetaDataType type);
// Meta-data
void releaseMetaData();
const MetaData* loadMetaData(PxInputStream& inputStream, MetaDataType type);
const MetaData* getBinaryMetaData(MetaDataType type);
int getNbMetaClasses(MetaDataType type);
MetaClass* getMetaClass(unsigned int i, MetaDataType type) const;
MetaClass* getMetaClass(const char* name, MetaDataType type) const;
MetaClass* getMetaClass(PxConcreteType::Enum concreteType, MetaDataType type);
MetaData* mMetaData_Src;
MetaData* mMetaData_Dst;
// Convert
bool convert(const void* buffer, int fileSize);
void resetConvexFlags();
void _enumerateFields(const MetaClass* mc, ExtraDataEntry2* entries, int& nb, int baseOffset, MetaDataType type) const;
void _enumerateExtraData(const char* address, const MetaClass* mc, ExtraDataEntry* entries, int& nb, int offset, MetaDataType type) const;
PxU64 read64(const void*& buffer);
int read32(const void*& buffer);
short read16(const void*& buffer);
bool convertClass(const char* buffer, const MetaClass* mc, int offset);
const char* convertExtraData_Array(const char* Address, const char* lastAddress, const char* objectAddress, const ExtraDataEntry& ed);
const char* convertExtraData_Ptr(const char* Address, const char* lastAddress, const PxMetaDataEntry& entry, int count, int ptrSize_Src, int ptrSize_Dst);
const char* convertExtraData_Handle(const char* Address, const char* lastAddress, const PxMetaDataEntry& entry, int count);
int getConcreteType(const char* buffer);
bool convertCollection(const void* buffer, int fileSize, int nbObjects);
const void* convertManifestTable(const void* buffer, int& fileSize);
const void* convertImportReferences(const void* buffer, int& fileSize);
const void* convertExportReferences(const void* buffer, int& fileSize);
const void* convertInternalReferences(const void* buffer, int& fileSize);
const void* convertReferenceTables(const void* buffer, int& fileSize, int& nbObjectsInCollection);
bool checkPaddingBytes(const char* buffer, int byteCount);
// ---- big convex surgery ----
PsArray<bool> mConvexFlags;
// Align
const char* alignStream(const char* buffer, int alignment=ALIGN_DEFAULT);
void alignTarget(int alignment);
char mZeros[CONVX_ZERO_BUFFER_SIZE];
// Unions
bool registerUnion(const char* name);
bool registerUnionType(const char* unionName, const char* typeName, int typeValue);
const char* getTypeName(const char* unionName, int typeValue);
void resetUnions();
PsArray<Union> mUnions;
// Output
void setNullPtr(bool);
void setNoOutput(bool);
bool initOutput(PxOutputStream& targetStream);
void closeOutput();
int getCurrentOutputSize();
void output(short value);
void output(int value);
void output(PxU64 value);
void output(const char* buffer, int nbBytes);
void convert8 (const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry);
void convertPad8 (const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry);
void convert16 (const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry);
void convert32 (const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry);
void convert64 (const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry);
void convertFloat(const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry);
void convertPtr (const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry);
void convertHandle16(const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry);
PxOutputStream* mOutStream;
bool mMustFlip;
int mOutputSize;
int mSrcPtrSize;
int mDstPtrSize;
bool mNullPtr;
bool mNoOutput;
bool mMarkedPadding;
// Errors
void resetNbErrors();
int getNbErrors() const;
void displayMessage(physx::PxErrorCode::Enum code, const char* format, ...);
int mNbErrors;
int mNbWarnings;
// Settings
PxConverterReportMode::Enum mReportMode;
bool mPerformConversion;
// Remap pointers
void exportIntAsPtr(int value);
void exportInt(int value);
void exportInt64(PxU64 value);
PointerRemap mPointerRemap;
PointerRemap* mPointerActiveRemap;
PxU32 mPointerRemapCounter;
Handle16Remap mHandle16Remap;
Handle16Remap* mHandle16ActiveRemap;
PxU16 mHandle16RemapCounter;
friend class MetaData;
friend struct MetaClass;
};
} }
#endif

View File

@ -0,0 +1,63 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
#include "SnConvX.h"
#include "SnConvX_Align.h"
#include <assert.h>
using namespace physx;
void Sn::ConvX::alignTarget(int alignment)
{
const int outputSize = getCurrentOutputSize();
const PxU32 outPadding = getPadding(size_t(outputSize), PxU32(alignment));
if(outPadding)
{
assert(outPadding<CONVX_ZERO_BUFFER_SIZE);
output(mZeros, int(outPadding));
}
}
const char* Sn::ConvX::alignStream(const char* buffer, int alignment)
{
const PxU32 padding = getPadding(size_t(buffer), PxU32(alignment));
assert(!getPadding(size_t(buffer + padding), PxU32(alignment)));
const int outputSize = getCurrentOutputSize();
const PxU32 outPadding = getPadding(size_t(outputSize), PxU32(alignment));
if(outPadding==padding)
{
assert(outPadding<CONVX_ZERO_BUFFER_SIZE);
output(mZeros, int(outPadding));
}
else if(outPadding)
{
assert(outPadding<CONVX_ZERO_BUFFER_SIZE);
output(mZeros, int(outPadding));
}
return buffer + padding;
}

View File

@ -0,0 +1,44 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
#ifndef PX_CONVX_ALIGN_H
#define PX_CONVX_ALIGN_H
namespace physx { namespace Sn {
#define ALIGN_DEFAULT 16
#define ALIGN_FILE 128
PX_INLINE PxU32 getPadding(size_t value, PxU32 alignment)
{
const PxU32 mask = alignment-1;
const PxU32 overhead = PxU32(value) & mask;
return (alignment - overhead) & mask;
}
} }
#endif

View File

@ -0,0 +1,43 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
#ifndef PX_CONVX_COMMON_H
#define PX_CONVX_COMMON_H
#if PX_VC
#pragma warning(disable:4121) // alignment of a member was sensitive to packing
#endif
#include "common/PxPhysXCommonConfig.h"
#define DELETESINGLE(x) if(x){ delete x; x = NULL; }
#define DELETEARRAY(x) if(x){ delete []x; x = NULL; }
#define inline_ PX_FORCE_INLINE
#define PsArray physx::shdfnd::Array
#endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,92 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
#include "foundation/PxErrorCallback.h"
#include "SnConvX.h"
#include <stdarg.h>
#include "PsString.h"
#include "PsFoundation.h"
#define MAX_DISPLAYED_ISSUES 10
using namespace physx;
void Sn::ConvX::resetNbErrors()
{
mNbErrors = 0;
mNbWarnings = 0;
}
int Sn::ConvX::getNbErrors() const
{
return mNbErrors;
}
void Sn::ConvX::displayMessage(PxErrorCode::Enum code, const char* format, ...)
{
if(silentMode())
return;
int sum = mNbWarnings + mNbErrors;
if(sum >= MAX_DISPLAYED_ISSUES)
return;
bool display = false;
if(code==PxErrorCode::eINTERNAL_ERROR || code==PxErrorCode::eINVALID_OPERATION || code==PxErrorCode::eINVALID_PARAMETER)
{
mNbErrors++;
display = true;
}
else if(code == PxErrorCode::eDEBUG_WARNING)
{
mNbWarnings++;
display = true;
}
if(display || ((sum == 0) && verboseMode()) )
{
va_list va;
va_start(va, format);
Ps::getFoundation().errorImpl(code, __FILE__, __LINE__, format, va);
va_end(va);
}
if(display)
{
if( sum == 0)
{
Ps::getFoundation().error(PxErrorCode::eDEBUG_INFO, __FILE__, __LINE__, "Hit warnings or errors: skipping further verbose output.\n");
}
else if(sum == MAX_DISPLAYED_ISSUES-1)
{
Ps::getFoundation().error(PxErrorCode::eDEBUG_INFO, __FILE__, __LINE__, "Exceeding 10 warnings or errors: skipping further output.\n");
}
}
return;
}

View File

@ -0,0 +1,953 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
#include "foundation/PxIO.h"
#include "foundation/PxMemory.h"
#include "SnConvX.h"
#include "common/PxSerialFramework.h"
#include "serialization/SnSerialUtils.h"
#include <assert.h>
using namespace physx;
using namespace physx::Sn;
//#define REMOVE_EXPLICIT_PADDING
static const char gVTablePtr[] = "v-table ptr";
static const char gAutoPadding[] = "auto-generated padding";
static const char gByte[] = "paddingByte";
///////////////////////////////////////////////////////////////////////////////
bool PxMetaDataEntry::isVTablePtr() const
{
return mType==gVTablePtr;
}
///////////////////////////////////////////////////////////////////////////////
bool MetaClass::getFieldByType(const char* type, PxMetaDataEntry& entry) const
{
assert(type);
PxU32 nbFields = mFields.size();
for(PxU32 i=0;i<nbFields;i++)
{
if(strcmp(mFields[i].mType, type)==0)
{
entry = mFields[i];
return true;
}
}
return false;
}
bool MetaClass::getFieldByName(const char* name, PxMetaDataEntry& entry) const
{
assert(name);
PxU32 nbFields = mFields.size();
for(PxU32 i=0;i<nbFields;i++)
{
if(strcmp(mFields[i].mName, name)==0)
{
entry = mFields[i];
return true;
}
}
return false;
}
void MetaClass::checkAndCompleteClass(const MetaData& owner, int& startOffset, int& nbBytes)
{
if(startOffset!=-1)
{
owner.mConvX.displayMessage(PxErrorCode::eDEBUG_INFO,
"\n Adding %d padding bytes at offset %d in class %s.\n", nbBytes, startOffset, mClassName);
// Leap of faith: add padding bytes there
PxMetaDataEntry padding;
padding.mType = gByte;
padding.mName = gAutoPadding;
padding.mOffset = startOffset;
padding.mSize = nbBytes;
padding.mCount = nbBytes;
padding.mFlags = PxMetaDataFlag::ePADDING;
mFields.pushBack(padding);
startOffset = -1;
}
}
bool MetaClass::check(const MetaData& owner)
{
owner.mConvX.displayMessage(PxErrorCode::eDEBUG_INFO, "Checking class: %s\n", mClassName);
if(mCallback)
return true; // Skip atomic types
if(mMaster)
return true; // Skip typedefs
bool* map = reinterpret_cast<bool*>(PX_ALLOC(sizeof(bool)*mSize, "bool"));
memset(map, 0, size_t(mSize));
const PxU32 nbFields = mFields.size();
for(PxU32 i=0;i<nbFields;i++)
{
const PxMetaDataEntry& field = mFields[i];
if(field.mFlags & PxMetaDataFlag::eEXTRA_DATA)
continue;
// if((field.mFlags & PxMetaDataFlag::eUNION) && !field.mSize)
// continue; // Union type
assert(field.mSize);
const int byteStart = field.mOffset;
const int byteEnd = field.mOffset + field.mSize;
assert(byteStart>=0 && byteStart<mSize);
assert(byteEnd>=0 && byteEnd<=mSize);
int startOffset = -1;
int nbBytes = 0;
for(int j=byteStart;j<byteEnd;j++)
{
if(map[j])
{
if(startOffset==-1)
{
startOffset = int(i);
nbBytes = 0;
}
nbBytes++;
// displayErrorMessage(" %s: found overlapping bytes!\n", mClassName);
}
else
{
if(startOffset!=-1)
{
owner.mConvX.displayMessage(PxErrorCode::eINTERNAL_ERROR,
"PxBinaryConverter: %s: %d overlapping bytes at offset %d!\n", mClassName, nbBytes, startOffset);
startOffset = -1;
PX_FREE(map);
return false;
}
}
map[j] = true;
}
if(startOffset!=-1)
{
owner.mConvX.displayMessage(PxErrorCode::eINTERNAL_ERROR,
"PxBinaryConverter: %s: %d overlapping bytes at offset %d!\n", mClassName, nbBytes, startOffset);
startOffset = -1;
PX_FREE(map);
return false;
}
}
{
int startOffset = -1;
int nbBytes = 0;
for(int i=0;i<mSize;i++)
{
if(!map[i])
{
if(startOffset==-1)
{
startOffset = i;
nbBytes = 0;
}
nbBytes++;
}
else
{
checkAndCompleteClass(owner, startOffset, nbBytes);
}
}
checkAndCompleteClass(owner, startOffset, nbBytes);
}
PX_FREE(map);
//
for(PxU32 i=0;i<nbFields;i++)
{
const PxMetaDataEntry& current = mFields[i];
if(current.mFlags & PxMetaDataFlag::ePTR)
continue;
MetaClass* fieldMetaClass = owner.mConvX.getMetaClass(current.mType, owner.getType());
if(!fieldMetaClass)
{
owner.mConvX.displayMessage(PxErrorCode::eINTERNAL_ERROR,
"PxBinaryConverter: Missing meta-data for: %s\n", current.mType);
return false;
}
else
{
if(current.mFlags & PxMetaDataFlag::eEXTRA_DATA)
{
owner.mConvX.displayMessage(PxErrorCode::eDEBUG_INFO, "Extra data: %s\n", current.mType);
}
else
{
assert(fieldMetaClass->mSize*current.mCount==current.mSize);
}
}
}
return true;
}
///////////////////////////////////////////////////////////////////////////////
MetaData::MetaData(ConvX& convx) :
mConvX (convx),
mType (META_DATA_NONE),
mNbEntries (0),
mEntries (NULL),
mStringTable (NULL),
mVersion (0),
mSizeOfPtr (0),
mPlatformTag (0),
mGaussMapLimit (0),
mFlip (false)
{
}
MetaData::~MetaData()
{
PxU32 nbMetaClasses = mMetaClasses.size();
for(PxU32 i=0;i<nbMetaClasses;i++)
{
MetaClass* current = mMetaClasses[i];
PX_DELETE(current);
}
PX_FREE(mStringTable);
PX_DELETE_ARRAY(mEntries);
}
MetaClass* MetaData::getMetaClass(const char* name) const
{
PxU32 nbMetaClasses = mMetaClasses.size();
for(PxU32 i=0;i<nbMetaClasses;i++)
{
MetaClass* current = mMetaClasses[i];
if(strcmp(current->mClassName, name)==0)
{
while(current->mMaster)
current = current->mMaster;
return current;
}
}
return NULL;
}
MetaClass* MetaData::getMetaClass(PxConcreteType::Enum concreteType) const
{
for(PxU32 i=0; i< mConcreteTypeTable.size(); i++)
{
if(mConcreteTypeTable[i].first == concreteType)
{
const char* className = offsetToText(reinterpret_cast<const char*>(size_t(mConcreteTypeTable[i].second)));
return getMetaClass(className);
}
}
return NULL;
}
MetaClass* MetaData::addNewClass(const char* name, int size, MetaClass* master, ConvertCallback callback)
{
// PT: if you reach this assert, you used PX_DEF_BIN_METADATA_TYPEDEF twice on the same type
assert(!getMetaClass(name));
MetaClass* mc = PX_NEW(MetaClass);
mc->mCallback = callback;
mc->mMaster = master;
mc->mClassName = name;
mc->mSize = size;
mc->mDepth = 0;
mc->mProcessed = false;
// mc->mNbEntries = -1;
mMetaClasses.pushBack(mc);
return mc;
}
bool MetaData::load(PxInputStream& inputStream, MetaDataType type)
{
assert(type!=META_DATA_NONE);
mConvX.displayMessage(PxErrorCode::eDEBUG_INFO, "Loading %s meta-data...\n", type==META_DATA_SRC ? "source" : "target");
mType = type;
mFlip = false;
{
int header;
inputStream.read(&header, 4);
if(header==PX_MAKE_FOURCC('M','E','T','A'))
{
mFlip = false;
}
else if(header==PX_MAKE_FOURCC('A','T','E','M'))
{
mFlip = true;
}
else
{
mConvX.displayMessage(PxErrorCode::eINVALID_PARAMETER, "PxBinaryConverter: invalid meta-data file!\n");
return false;
}
if (type == META_DATA_SRC && mFlip)
{
mConvX.displayMessage(PxErrorCode::eINVALID_PARAMETER,
"PxBinaryConverter: source meta data needs to match endianness with current system!");
return false;
}
inputStream.read(&mVersion, 4);
if(mFlip)
{
flip(mVersion);
}
inputStream.read(mBinaryVersionGuid, SN_BINARY_VERSION_GUID_NUM_CHARS);
mBinaryVersionGuid[SN_BINARY_VERSION_GUID_NUM_CHARS] = 0;
if (!checkCompatibility(mBinaryVersionGuid))
{
mConvX.displayMessage(PxErrorCode::eINVALID_PARAMETER,
"PxBinaryConverter: binary data version 0x%s is incompatible with this PhysX sdk (0x%s).\n",
mBinaryVersionGuid, getBinaryVersionGuid());
return false;
}
inputStream.read(&mSizeOfPtr, 4);
if(mFlip)
flip(mSizeOfPtr);
inputStream.read(&mPlatformTag, 4);
if(mFlip)
flip(mPlatformTag);
if (!Sn::isBinaryPlatformTagValid(PxU32(mPlatformTag)))
{
mConvX.displayMessage(PxErrorCode::eINVALID_PARAMETER, "PxBinaryConverter: Unknown meta data platform tag");
return false;
}
inputStream.read(&mGaussMapLimit, 4);
if(mFlip)
flip(mGaussMapLimit);
inputStream.read(&mNbEntries, 4);
if(mFlip)
flip(mNbEntries);
mEntries = PX_NEW(PxMetaDataEntry)[PxU32(mNbEntries)];
if(mSizeOfPtr==8)
{
for(int i=0;i<mNbEntries;i++)
{
MetaDataEntry64 tmp;
inputStream.read(&tmp, sizeof(MetaDataEntry64));
if (mFlip) // important to flip them first, else the cast below might destroy information
{
flip(tmp.mType);
flip(tmp.mName);
}
// We can safely cast to 32bits here since we transformed the pointers to offsets in the string table on export
mEntries[i].mType = reinterpret_cast<const char*>(size_t(tmp.mType));
mEntries[i].mName = reinterpret_cast<const char*>(size_t(tmp.mName));
mEntries[i].mOffset = tmp.mOffset;
mEntries[i].mSize = tmp.mSize;
mEntries[i].mCount = tmp.mCount;
mEntries[i].mOffsetSize = tmp.mOffsetSize;
mEntries[i].mFlags = tmp.mFlags;
mEntries[i].mAlignment = tmp.mAlignment;
}
}
else
{
assert(mSizeOfPtr==4);
// inputStream.read(mEntries, mNbEntries*sizeof(PxMetaDataEntry));
for(int i=0;i<mNbEntries;i++)
{
MetaDataEntry32 tmp;
inputStream.read(&tmp, sizeof(MetaDataEntry32));
if (mFlip)
{
flip(tmp.mType);
flip(tmp.mName);
}
mEntries[i].mType = reinterpret_cast<const char*>(size_t(tmp.mType));
mEntries[i].mName = reinterpret_cast<const char*>(size_t(tmp.mName));
mEntries[i].mOffset = tmp.mOffset;
mEntries[i].mSize = tmp.mSize;
mEntries[i].mCount = tmp.mCount;
mEntries[i].mOffsetSize = tmp.mOffsetSize;
mEntries[i].mFlags = tmp.mFlags;
mEntries[i].mAlignment = tmp.mAlignment;
}
}
if(mFlip)
{
for(int i=0;i<mNbEntries;i++)
{
// mEntries[i].mType and mEntries[i].mName have been flipped already because they need special treatment
// on 64bit to 32bit platform conversions
flip(mEntries[i].mOffset);
flip(mEntries[i].mSize);
flip(mEntries[i].mCount);
flip(mEntries[i].mOffsetSize);
flip(mEntries[i].mFlags);
flip(mEntries[i].mAlignment);
}
}
int nbConcreteType;
inputStream.read(&nbConcreteType, 4);
if(mFlip)
flip(nbConcreteType);
for(int i=0; i<nbConcreteType; i++)
{
PxU16 concreteType;
PxU32 nameOffset;
inputStream.read(&concreteType, 2);
inputStream.read(&nameOffset, 4);
if(mFlip)
{
flip(concreteType);
flip(nameOffset);
}
mConcreteTypeTable.pushBack( Ps::Pair<PxConcreteType::Enum, PxU32>(PxConcreteType::Enum(concreteType), nameOffset) );
}
int tableSize;
inputStream.read(&tableSize, 4);
if(mFlip)
flip(tableSize);
mStringTable = reinterpret_cast<char*>(PX_ALLOC(sizeof(char)*tableSize, "MetaData StringTable"));
inputStream.read(mStringTable, PxU32(tableSize));
}
// Register atomic types
{
addNewClass("bool", 1, NULL, &ConvX::convert8);
addNewClass("char", 1, NULL, &ConvX::convert8);
addNewClass("short", 2, NULL, &ConvX::convert16);
addNewClass("int", 4, NULL, &ConvX::convert32);
addNewClass("PxU64", 8, NULL, &ConvX::convert64);
addNewClass("float", 4, NULL, &ConvX::convertFloat);
addNewClass("paddingByte", 1, NULL, &ConvX::convertPad8);
}
{
MetaClass* currentClass = NULL;
for(int i=0;i<mNbEntries;i++)
{
mEntries[i].mType = offsetToText(mEntries[i].mType);
mEntries[i].mName = offsetToText(mEntries[i].mName);
if(mEntries[i].mFlags & PxMetaDataFlag::eTYPEDEF)
{
mConvX.displayMessage(PxErrorCode::eDEBUG_INFO, "Found typedef: %s => %s\n", mEntries[i].mName, mEntries[i].mType);
MetaClass* mc = getMetaClass(mEntries[i].mName);
if(mc)
addNewClass(mEntries[i].mType, mc->mSize, mc, mc->mCallback);
else
mConvX.displayMessage(PxErrorCode::eINTERNAL_ERROR,
"PxBinaryConverter: Invalid typedef - Missing metadata for: %s, please check the source metadata.\n"
, mEntries[i].mName);
}
else if(mEntries[i].mFlags & PxMetaDataFlag::eCLASS)
{
if(!mEntries[i].mName)
{
mConvX.displayMessage(PxErrorCode::eDEBUG_INFO, "Found class: %s\n", mEntries[i].mType);
currentClass = addNewClass(mEntries[i].mType, mEntries[i].mSize);
if(mEntries[i].mFlags & PxMetaDataFlag::eVIRTUAL)
{
PxMetaDataEntry vtable;
vtable.mType = gVTablePtr;
vtable.mName = gVTablePtr;
vtable.mOffset = 0;
vtable.mSize = mSizeOfPtr;
vtable.mCount = 1;
vtable.mFlags = PxMetaDataFlag::ePTR;
currentClass->mFields.pushBack(vtable);
}
}
else
{
assert(currentClass);
mConvX.displayMessage(PxErrorCode::eDEBUG_INFO, " - inherits from: %s\n", mEntries[i].mName);
currentClass->mBaseClasses.pushBack(mEntries[i]);
}
}
else
{
const int isUnion = mEntries[i].mFlags & PxMetaDataFlag::eUNION;
if(isUnion && !mEntries[i].mSize)
{
mConvX.registerUnionType(mEntries[i].mType, mEntries[i].mName, mEntries[i].mOffset);
}
else
{
if(isUnion)
{
mConvX.registerUnion(mEntries[i].mType);
}
const int isPadding = mEntries[i].mFlags & PxMetaDataFlag::ePADDING;
assert(currentClass);
#ifdef REMOVE_EXPLICIT_PADDING
if(!isPadding)
#endif
currentClass->mFields.pushBack(mEntries[i]);
if(isPadding)
mConvX.displayMessage(PxErrorCode::eDEBUG_INFO,
" - contains padding: %s - %s\n", mEntries[i].mType, mEntries[i].mName);
else if(mEntries[i].mFlags & PxMetaDataFlag::eEXTRA_DATA)
mConvX.displayMessage(PxErrorCode::eDEBUG_INFO,
" - contains extra data: %s%s\n", mEntries[i].mType, mEntries[i].mFlags & PxMetaDataFlag::ePTR ? "*" : "");
else
mConvX.displayMessage(PxErrorCode::eDEBUG_INFO,
" - contains field: %s%s\n", mEntries[i].mType, mEntries[i].mFlags & PxMetaDataFlag::ePTR ? "*" : "");
}
}
}
}
// Sort classes by depth
struct Local
{
static bool _computeDepth(const MetaData& md, MetaClass* current, int currentDepth, int& maxDepth)
{
if(currentDepth>maxDepth)
maxDepth = currentDepth;
PxU32 nbBases = current->mBaseClasses.size();
for(PxU32 i=0;i<nbBases;i++)
{
const PxMetaDataEntry& baseClassEntry = current->mBaseClasses[i];
MetaClass* baseClass = md.getMetaClass(baseClassEntry.mName);
if(!baseClass)
{
md.mConvX.displayMessage(PxErrorCode::eINTERNAL_ERROR,
"PxBinaryConverter: Can't find class %s metadata, please check the source metadata.\n", baseClassEntry.mName);
return false;
}
if (!_computeDepth(md, baseClass, currentDepth+1, maxDepth))
return false;
}
return true;
}
static int compareClasses(const void* c0, const void* c1)
{
MetaClass** mc0 = reinterpret_cast<MetaClass**>(const_cast<void*>(c0));
MetaClass** mc1 = reinterpret_cast<MetaClass**>(const_cast<void*>(c1));
// return (*mc0)->mSize - (*mc1)->mSize;
return (*mc0)->mDepth - (*mc1)->mDepth;
}
static int compareEntries(const void* c0, const void* c1)
{
PxMetaDataEntry* mc0 = reinterpret_cast<PxMetaDataEntry*>(const_cast<void*>(c0));
PxMetaDataEntry* mc1 = reinterpret_cast<PxMetaDataEntry*>(const_cast<void*>(c1));
//mOffset is used to access control information for extra data, and not for offsets of the data itself.
assert(!(mc0->mFlags & PxMetaDataFlag::eEXTRA_DATA));
assert(!(mc1->mFlags & PxMetaDataFlag::eEXTRA_DATA));
return mc0->mOffset - mc1->mOffset;
}
};
{
// Compute depths
const PxU32 nbMetaClasses = mMetaClasses.size();
for(PxU32 i=0;i<nbMetaClasses;i++)
{
MetaClass* current = mMetaClasses[i];
int maxDepth = 0;
if(!Local::_computeDepth(*this, current, 0, maxDepth))
return false;
current->mDepth = maxDepth;
}
// Sort by depth
MetaClass** metaClasses = &mMetaClasses[0];
qsort(metaClasses, size_t(nbMetaClasses), sizeof(MetaClass*), Local::compareClasses);
}
// Replicate fields from base classes
{
PxU32 nbMetaClasses = mMetaClasses.size();
for(PxU32 k=0;k<nbMetaClasses;k++)
{
MetaClass* current = mMetaClasses[k];
PxU32 nbBases = current->mBaseClasses.size();
// merge entries of base classes and current class in the right order
// this is needed for extra data ordering, which is not covered by the mOffset sort
// in the next stage below
PsArray<PxMetaDataEntry> mergedEntries;
for(PxU32 i=0;i<nbBases;i++)
{
const PxMetaDataEntry& baseClassEntry = current->mBaseClasses[i];
MetaClass* baseClass = getMetaClass(baseClassEntry.mName);
assert(baseClass);
assert(baseClass->mBaseClasses.size()==0 || baseClass->mProcessed);
PxU32 nbBaseFields = baseClass->mFields.size();
for(PxU32 j=0;j<nbBaseFields;j++)
{
PxMetaDataEntry f = baseClass->mFields[j];
// Don't merge primary v-tables to avoid redundant v-table entries.
// It means the base v-table won't be inherited & needs to be explicitly defined in the metadata. Seems reasonable.
// Could be done better though.
if(f.mType==gVTablePtr && !f.mOffset && !baseClassEntry.mOffset)
continue;
f.mOffset += baseClassEntry.mOffset;
mergedEntries.pushBack(f);
}
current->mProcessed = true;
}
//append current fields to base class fields
for (PxU32 i = 0; i < current->mFields.size(); i++)
{
mergedEntries.pushBack(current->mFields[i]);
}
current->mFields.clear();
current->mFields.assign(mergedEntries.begin(), mergedEntries.end());
}
}
// Check classes
{
PxU32 nbMetaClasses = mMetaClasses.size();
for(PxU32 i=0;i<nbMetaClasses;i++)
{
MetaClass* current = mMetaClasses[i];
if(!current->check(*this))
return false;
}
}
// Sort meta-data by offset
{
PxU32 nbMetaClasses = mMetaClasses.size();
for(PxU32 i=0;i<nbMetaClasses;i++)
{
MetaClass* current = mMetaClasses[i];
PxU32 nbFields = current->mFields.size();
if(nbFields<2)
continue;
PxMetaDataEntry* entries = &current->mFields[0];
PxMetaDataEntry* newEntries = PX_NEW(PxMetaDataEntry)[nbFields];
PxU32 nb = 0;
for(PxU32 j=0;j<nbFields;j++)
if(!(entries[j].mFlags & PxMetaDataFlag::eEXTRA_DATA))
newEntries[nb++] = entries[j];
PxU32 nbToSort = nb;
for(PxU32 j=0;j<nbFields;j++)
if(entries[j].mFlags & PxMetaDataFlag::eEXTRA_DATA)
newEntries[nb++] = entries[j];
assert(nb==nbFields);
PxMemCopy(entries, newEntries, nb*sizeof(PxMetaDataEntry));
PX_DELETE_ARRAY(newEntries);
qsort(entries, size_t(nbToSort), sizeof(PxMetaDataEntry), Local::compareEntries);
}
}
return true;
}
namespace
{
//tool functions for MetaData::compare
bool str_equal(const char* src, const char* dst)
{
if (src == dst)
return true;
if (src != nullptr && dst != nullptr)
return strcmp(src, dst) == 0;
return false;
}
const char* str_print(const char* str)
{
return str != nullptr ? str : "(nullptr)";
}
}
#define COMPARE_METADATA_BOOL_MD(type, src, dst, field) if ((src).field != (dst).field) \
{ mConvX.displayMessage(PxErrorCode::eDEBUG_INFO, "%s::%s missmatch: src %s dst %s\n", #type, #field, (src).field?"true":"false", (dst).field?"true":"false"); isEquivalent = false; }
#define COMPARE_METADATA_INT_MD(type, src, dst, field) if ((src).field != (dst).field) \
{ mConvX.displayMessage(PxErrorCode::eDEBUG_INFO, "%s::%s missmatch: src %d dst %d\n", #type, #field, (src).field, (dst).field); isEquivalent = false; }
#define COMPARE_METADATA_STRING_MD(type, src, dst, field) \
if (!str_equal((src).field, (dst).field)) \
{ \
mConvX.displayMessage(PxErrorCode::eDEBUG_INFO, "%s::%s missmatch: src %s dst %s\n", #type, #field, str_print((src).field), str_print((dst).field)); \
isEquivalent = false; \
}
bool MetaData::compare(const MetaData& dst) const
{
bool isEquivalent = true;
//mType
COMPARE_METADATA_BOOL_MD(MetaData, *this, dst, mFlip)
//mVersion
COMPARE_METADATA_STRING_MD(MetaData, *this, dst, mBinaryVersionGuid)
COMPARE_METADATA_INT_MD(MetaData, *this, dst, mSizeOfPtr)
COMPARE_METADATA_INT_MD(MetaData, *this, dst, mPlatformTag)
COMPARE_METADATA_INT_MD(MetaData, *this, dst, mGaussMapLimit)
COMPARE_METADATA_INT_MD(MetaData, *this, dst, mNbEntries)
//find classes missing in dst
for (PxU32 i = 0; i<mMetaClasses.size(); i++)
{
MetaClass* mcSrc = mMetaClasses[i];
MetaClass* mcDst = dst.getMetaClass(mcSrc->mClassName);
if (mcDst == nullptr)
{
mConvX.displayMessage(PxErrorCode::eDEBUG_INFO, "dst is missing meta class %s", mcSrc->mClassName);
}
}
//find classes missing in src
for (PxU32 i = 0; i<dst.mMetaClasses.size(); i++)
{
MetaClass* mcDst = dst.mMetaClasses[i];
MetaClass* mcSrc = getMetaClass(mcDst->mClassName);
if (mcSrc == nullptr)
{
mConvX.displayMessage(PxErrorCode::eDEBUG_INFO, "src is missing meta class %s", mcDst->mClassName);
}
}
//compare classes present in src and dst
for (PxU32 i = 0; i<mMetaClasses.size(); i++)
{
const char* className = mMetaClasses[i]->mClassName;
MetaClass* mcSrc = getMetaClass(className);
MetaClass* mcDst = dst.getMetaClass(className);
if (mcSrc != nullptr && mcDst != nullptr)
{
COMPARE_METADATA_INT_MD(MetaClass, *mcSrc, *mcDst, mCallback)
COMPARE_METADATA_INT_MD(MetaClass, *mcSrc, *mcDst, mMaster) //should be 0 for both anyway
COMPARE_METADATA_STRING_MD(MetaClass, *mcSrc, *mcDst, mClassName)
COMPARE_METADATA_INT_MD(MetaClass, *mcSrc, *mcDst, mSize)
COMPARE_METADATA_INT_MD(MetaClass, *mcSrc, *mcDst, mDepth)
COMPARE_METADATA_INT_MD(MetaClass, *mcSrc, *mcDst, mBaseClasses.size())
if (mcSrc->mBaseClasses.size() == mcDst->mBaseClasses.size())
{
for (PxU32 b = 0; b < mcSrc->mBaseClasses.size(); b++)
{
COMPARE_METADATA_STRING_MD(PxMetaDataEntry, mcSrc->mBaseClasses[b], mcDst->mBaseClasses[b], mName);
}
}
COMPARE_METADATA_INT_MD(MetaClass, *mcSrc, *mcDst, mFields.size())
if (mcSrc->mFields.size() == mcDst->mFields.size())
{
for (PxU32 f = 0; f < mcSrc->mFields.size(); f++)
{
PxMetaDataEntry srcMde = mcSrc->mFields[f];
PxMetaDataEntry dstMde = mcDst->mFields[f];
COMPARE_METADATA_STRING_MD(PxMetaDataEntry, srcMde, dstMde, mType)
COMPARE_METADATA_STRING_MD(PxMetaDataEntry, srcMde, dstMde, mName)
COMPARE_METADATA_INT_MD(PxMetaDataEntry, srcMde, dstMde, mOffset)
COMPARE_METADATA_INT_MD(PxMetaDataEntry, srcMde, dstMde, mSize)
COMPARE_METADATA_INT_MD(PxMetaDataEntry, srcMde, dstMde, mCount)
COMPARE_METADATA_INT_MD(PxMetaDataEntry, srcMde, dstMde, mOffsetSize)
COMPARE_METADATA_INT_MD(PxMetaDataEntry, srcMde, dstMde, mFlags)
COMPARE_METADATA_INT_MD(PxMetaDataEntry, srcMde, dstMde, mAlignment)
}
}
}
}
return isEquivalent;
}
#undef COMPARE_METADATA_BOOL_MD
#undef COMPARE_METADATA_INT_MD
#undef COMPARE_METADATA_STRING_MD
///////////////////////////////////////////////////////////////////////////////
void ConvX::releaseMetaData()
{
DELETESINGLE(mMetaData_Dst);
DELETESINGLE(mMetaData_Src);
}
const MetaData* ConvX::loadMetaData(PxInputStream& inputStream, MetaDataType type)
{
if (type != META_DATA_SRC && type != META_DATA_DST)
{
displayMessage(PxErrorCode::eINTERNAL_ERROR,
"PxBinaryConverter: Wrong meta data type, please check the source metadata.\n");
return NULL;
}
PX_ASSERT(type == META_DATA_SRC || type == META_DATA_DST);
MetaData*& metaDataPtr = (type == META_DATA_SRC) ? mMetaData_Src : mMetaData_Dst;
metaDataPtr = PX_NEW(MetaData)(*this);
if(!(metaDataPtr)->load(inputStream, type))
DELETESINGLE(metaDataPtr);
return metaDataPtr;
}
const MetaData* ConvX::getBinaryMetaData(MetaDataType type)
{
if(type==META_DATA_SRC)
return mMetaData_Src;
if(type==META_DATA_DST)
return mMetaData_Dst;
PX_ASSERT(0);
return NULL;
}
int ConvX::getNbMetaClasses(MetaDataType type)
{
if(type==META_DATA_SRC)
return mMetaData_Src->getNbMetaClasses();
if(type==META_DATA_DST)
return mMetaData_Dst->getNbMetaClasses();
PX_ASSERT(0);
return 0;
}
MetaClass* ConvX::getMetaClass(unsigned int i, MetaDataType type) const
{
if(type==META_DATA_SRC)
return mMetaData_Src->getMetaClass(i);
if(type==META_DATA_DST)
return mMetaData_Dst->getMetaClass(i);
PX_ASSERT(0);
return NULL;
}
MetaClass* ConvX::getMetaClass(const char* name, MetaDataType type) const
{
if(type==META_DATA_SRC)
return mMetaData_Src->getMetaClass(name);
if(type==META_DATA_DST)
return mMetaData_Dst->getMetaClass(name);
PX_ASSERT(0);
return NULL;
}
MetaClass* ConvX::getMetaClass(PxConcreteType::Enum concreteType, MetaDataType type)
{
MetaClass* metaClass = NULL;
if(type==META_DATA_SRC)
metaClass = mMetaData_Src->getMetaClass(concreteType);
if(type==META_DATA_DST)
metaClass = mMetaData_Dst->getMetaClass(concreteType);
if(!metaClass)
{
displayMessage(PxErrorCode::eINTERNAL_ERROR,
"PxBinaryConverter: Missing concreteType %d metadata! serialized a class without dumping metadata. Please check the metadata.",
concreteType);
return NULL;
}
return metaClass;
}
///////////////////////////////////////////////////////////////////////////////
// Peek & poke, yes sir.
PxU64 physx::Sn::peek(int size, const char* buffer, int flags)
{
const int maskMSB = flags & PxMetaDataFlag::eCOUNT_MASK_MSB;
const int skipIfOne = flags & PxMetaDataFlag::eCOUNT_SKIP_IF_ONE;
switch(size)
{
case 1:
{
unsigned char value = *(reinterpret_cast<const unsigned char*>(buffer));
if(maskMSB)
value &= 0x7f;
if(skipIfOne && value==1)
return 0;
return PxU64(value);
}
case 2:
{
unsigned short value = *(reinterpret_cast<const unsigned short*>(buffer));
if(maskMSB)
value &= 0x7fff;
if(skipIfOne && value==1)
return 0;
return PxU64(value);
}
case 4:
{
unsigned int value = *(reinterpret_cast<const unsigned int*>(buffer));
if(maskMSB)
value &= 0x7fffffff;
if(skipIfOne && value==1)
return 0;
return PxU64(value);
}
case 8:
{
PxU64 value = *(reinterpret_cast<const PxU64*>(buffer));
if(maskMSB)
value &= (PxU64(-1))>>1;
if(skipIfOne && value==1)
return 0;
return value;
}
};
PX_ASSERT(0);
return PxU64(-1);
}

View File

@ -0,0 +1,188 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
#ifndef PX_CONVX_METADATA_H
#define PX_CONVX_METADATA_H
#include "common/PxMetaDataFlags.h"
#include "SnConvX_Output.h"
#include "serialization/SnSerialUtils.h"
namespace physx { namespace Sn {
#if PX_VC
#pragma warning (push)
#pragma warning (disable : 4371) //layout of class may have changed from a previous version of the compiler due to better packing of member
#endif
// PT: beware, must match corresponding structure in PxMetaData.h
struct PxMetaDataEntry : public shdfnd::UserAllocated
{
PxMetaDataEntry()
{
memset(this, 0, sizeof(*this));
}
bool isVTablePtr() const;
const char* mType; //!< Field type (bool, byte, quaternion, etc)
const char* mName; //!< Field name (appears exactly as in the source file)
int mOffset; //!< Offset from the start of the class (ie from "this", field is located at "this"+Offset)
int mSize; //!< sizeof(Type)
int mCount; //!< Number of items of type Type (0 for dynamic sizes)
int mOffsetSize; //!< Offset of dynamic size param, for dynamic arrays
int mFlags; //!< Field parameters
int mAlignment; //!< Explicit alignment added for DE1340
};
struct MetaDataEntry32
{
PxI32 mType; //!< Field type (bool, byte, quaternion, etc)
PxI32 mName; //!< Field name (appears exactly as in the source file)
int mOffset; //!< Offset from the start of the class (ie from "this", field is located at "this"+Offset)
int mSize; //!< sizeof(Type)
int mCount; //!< Number of items of type Type (0 for dynamic sizes)
int mOffsetSize; //!< Offset of dynamic size param, for dynamic arrays
int mFlags; //!< Field parameters
int mAlignment; //!< Explicit alignment added for DE1340
};
struct MetaDataEntry64
{
PxI64 mType; //!< Field type (bool, byte, quaternion, etc)
PxI64 mName; //!< Field name (appears exactly as in the source file)
int mOffset; //!< Offset from the start of the class (ie from "this", field is located at "this"+Offset)
int mSize; //!< sizeof(Type)
int mCount; //!< Number of items of type Type (0 for dynamic sizes)
int mOffsetSize; //!< Offset of dynamic size param, for dynamic arrays
int mFlags; //!< Field parameters
int mAlignment; //!< Explicit alignment added for DE1340
};
struct ExtraDataEntry
{
PxMetaDataEntry entry;
int offset;
};
struct ExtraDataEntry2 : ExtraDataEntry
{
ConvertCallback cb;
};
class MetaData;
struct MetaClass : public shdfnd::UserAllocated
{
bool getFieldByType(const char* type, PxMetaDataEntry& entry) const;
bool getFieldByName(const char* name, PxMetaDataEntry& entry) const;
bool check(const MetaData& owner);
ConvertCallback mCallback;
MetaClass* mMaster;
const char* mClassName;
int mSize;
int mDepth;
PsArray<PxMetaDataEntry> mBaseClasses;
PsArray<PxMetaDataEntry> mFields;
bool mProcessed;
// int mNbEntries;
// ExtraDataEntry2 mEntries[256];
private:
void checkAndCompleteClass(const MetaData& owner, int& startOffset, int& nbBytes);
};
enum MetaDataType
{
META_DATA_NONE,
META_DATA_SRC,
META_DATA_DST
};
class ConvX;
class MetaData : public shdfnd::UserAllocated
{
public:
MetaData(Sn::ConvX&);
~MetaData();
bool load(PxInputStream& inputStream, MetaDataType type);
inline_ MetaDataType getType() const { return mType; }
inline_ int getVersion() const { return mVersion; }
inline_ int getPtrSize() const { return mSizeOfPtr; }
inline_ int getPlatformTag() const { return mPlatformTag; }
inline_ int getGaussMapLimit() const { return mGaussMapLimit; }
inline_ int getNbMetaClasses() const { return int(mMetaClasses.size()); }
inline_ MetaClass* getMetaClass(unsigned int i) const { return mMetaClasses[i]; }
inline_ bool getFlip() const { return mFlip; }
MetaClass* getMetaClass(const char* name) const;
MetaClass* getMetaClass(PxConcreteType::Enum concreteType) const;
MetaClass* addNewClass(const char* name, int size, MetaClass* master=NULL, ConvertCallback callback=NULL);
bool compare(const MetaData& candidate) const;
private:
MetaData& operator=(const MetaData&);
Sn::ConvX& mConvX;
MetaDataType mType;
int mNbEntries;
PxMetaDataEntry* mEntries;
char* mStringTable;
PsArray<MetaClass*> mMetaClasses;
int mVersion;
char mBinaryVersionGuid[SN_BINARY_VERSION_GUID_NUM_CHARS + 1];
int mSizeOfPtr;
int mPlatformTag;
int mGaussMapLimit;
bool mFlip;
PsArray< Ps::Pair<PxConcreteType::Enum, PxU32> > mConcreteTypeTable;
inline_ const char* offsetToText(const char* text) const
{
const size_t offset = size_t(text);
const PxU32 offset32 = PxU32(offset);
// if(offset==-1)
if(offset32==0xffffffff)
return NULL;
return mStringTable + offset32;
}
friend struct MetaClass;
};
PxU64 peek(int size, const char* buffer, int flags=0);
#if PX_VC
#pragma warning (pop)
#endif
} }
#endif

View File

@ -0,0 +1,492 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
#include "foundation/PxIO.h"
#include "foundation/PxErrorCallback.h"
#include "SnConvX.h"
#if PX_VC
#pragma warning(disable:4389) // signed/unsigned mismatch
#endif
using namespace physx;
void Sn::ConvX::setNullPtr(bool flag)
{
mNullPtr = flag;
}
void Sn::ConvX::setNoOutput(bool flag)
{
mNoOutput = flag;
}
bool Sn::ConvX::initOutput(PxOutputStream& targetStream)
{
mOutStream = &targetStream;
mOutputSize = 0;
mNullPtr = false;
mNoOutput = false;
const MetaData* srcMetaData = getBinaryMetaData(META_DATA_SRC);
PX_ASSERT(srcMetaData);
const MetaData* dstMetaData = getBinaryMetaData(META_DATA_DST);
PX_ASSERT(dstMetaData);
mSrcPtrSize = srcMetaData->getPtrSize();
mDstPtrSize = dstMetaData->getPtrSize();
PX_ASSERT(!srcMetaData->getFlip());
mMustFlip = dstMetaData->getFlip();
return true;
}
void Sn::ConvX::closeOutput()
{
mOutStream = NULL;
}
int Sn::ConvX::getCurrentOutputSize()
{
return mOutputSize;
}
void Sn::ConvX::output(short value)
{
if(mNoOutput)
return;
if(mMustFlip)
flip(value);
PX_ASSERT(mOutStream);
const size_t size = mOutStream->write(&value, 2);
PX_ASSERT(size==2);
mOutputSize += int(size);
}
void Sn::ConvX::output(int value)
{
if(mNoOutput)
return;
if(mMustFlip)
flip(value);
PX_ASSERT(mOutStream);
const size_t size = mOutStream->write(&value, 4);
PX_ASSERT(size==4);
mOutputSize += int(size);
}
//ntohll is a macro on apple yosemite
static PxU64 ntohll_internal(const PxU64 value)
{
union
{
PxU64 ull;
PxU8 c[8];
} x;
x.ull = value;
PxU8 c = 0;
c = x.c[0]; x.c[0] = x.c[7]; x.c[7] = c;
c = x.c[1]; x.c[1] = x.c[6]; x.c[6] = c;
c = x.c[2]; x.c[2] = x.c[5]; x.c[5] = c;
c = x.c[3]; x.c[3] = x.c[4]; x.c[4] = c;
return x.ull;
}
void Sn::ConvX::output(PxU64 value)
{
if(mNoOutput)
return;
if(mMustFlip)
// flip(value);
value = ntohll_internal(value);
PX_ASSERT(mOutStream);
const size_t size = mOutStream->write(&value, 8);
PX_ASSERT(size==8);
mOutputSize += int(size);
}
void Sn::ConvX::output(const char* buffer, int nbBytes)
{
if(mNoOutput)
return;
if(!nbBytes)
return;
PX_ASSERT(mOutStream);
const PxU32 size = mOutStream->write(buffer, PxU32(nbBytes));
PX_ASSERT(size== PxU32(nbBytes));
mOutputSize += int(size);
}
void Sn::ConvX::convert8(const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry)
{
(void)dstEntry;
if(mNoOutput)
return;
PX_ASSERT(entry.mSize==1*entry.mCount);
PX_ASSERT(mOutStream);
PX_ASSERT(entry.mSize==dstEntry.mSize);
const PxU32 size = mOutStream->write(src, PxU32(entry.mSize));
PX_ASSERT(size== PxU32(entry.mSize));
mOutputSize += int(size);
}
// This is called to convert auto-generated "padding bytes" (or so we think).
// We use a special converter to check the input bytes and issue warnings when it doesn't look like padding
void Sn::ConvX::convertPad8(const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry)
{
(void)dstEntry;
(void)src;
if(mNoOutput)
return;
PX_ASSERT(entry.mSize);
PX_ASSERT(entry.mSize==1*entry.mCount);
PX_ASSERT(mOutStream);
PX_ASSERT(entry.mSize==dstEntry.mSize);
// PT: we don't output the source data on purpose, to catch missing meta-data
// sschirm: changed that to 0xcd, so we can mark the output as "having marked pads"
const unsigned char b = 0xcd;
for(int i=0;i<entry.mSize;i++)
{
const size_t size = mOutStream->write(&b, 1);
(void)size;
}
mOutputSize += entry.mSize;
}
void Sn::ConvX::convert16(const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry)
{
(void)dstEntry;
if(mNoOutput)
return;
PX_ASSERT(entry.mSize==int(sizeof(short)*entry.mCount));
PX_ASSERT(mOutStream);
PX_ASSERT(entry.mSize==dstEntry.mSize);
const short* data = reinterpret_cast<const short*>(src);
for(int i=0;i<entry.mCount;i++)
{
short value = *data++;
if(mMustFlip)
flip(value);
const size_t size = mOutStream->write(&value, sizeof(short));
PX_ASSERT(size==sizeof(short));
mOutputSize += int(size);
}
}
void Sn::ConvX::convert32(const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry)
{
(void)dstEntry;
if(mNoOutput)
return;
PX_ASSERT(entry.mSize==int(sizeof(int)*entry.mCount));
PX_ASSERT(mOutStream);
PX_ASSERT(entry.mSize==dstEntry.mSize);
const int* data = reinterpret_cast<const int*>(src);
for(int i=0;i<entry.mCount;i++)
{
int value = *data++;
if(mMustFlip)
flip(value);
const size_t size = mOutStream->write(&value, sizeof(int));
PX_ASSERT(size==sizeof(int));
mOutputSize += int(size);
}
}
void Sn::ConvX::convert64(const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry)
{
(void)dstEntry;
if(mNoOutput)
return;
PX_ASSERT(entry.mSize==int(sizeof(PxU64)*entry.mCount));
PX_ASSERT(mOutStream);
PX_ASSERT(entry.mSize==dstEntry.mSize);
const PxU64* data = reinterpret_cast<const PxU64*>(src);
for(int i=0;i<entry.mCount;i++)
{
PxU64 value = *data++;
if(mMustFlip)
value = ntohll_internal(value);
const size_t size = mOutStream->write(&value, sizeof(PxU64));
PX_ASSERT(size==sizeof(PxU64));
mOutputSize += int(size);
}
}
void Sn::ConvX::convertFloat(const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry)
{
(void)dstEntry;
if(mNoOutput)
return;
PX_ASSERT(entry.mSize==int(sizeof(float)*entry.mCount));
PX_ASSERT(mOutStream);
PX_ASSERT(entry.mSize==dstEntry.mSize);
const float* data = reinterpret_cast<const float*>(src);
for(int i=0;i<entry.mCount;i++)
{
float value = *data++;
if(mMustFlip)
flip(value);
const size_t size = mOutStream->write(&value, sizeof(float));
PX_ASSERT(size==sizeof(float));
mOutputSize += int(size);
}
}
void Sn::ConvX::convertPtr(const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry)
{
(void)dstEntry;
if(mNoOutput)
return;
PX_ASSERT(entry.mSize==mSrcPtrSize*entry.mCount);
PX_ASSERT(mOutStream);
char buffer[16];
for(int i=0;i<entry.mCount;i++)
{
PxU64 testValue=0;
// Src pointer can be 4 or 8 bytes so we can't use "void*" here
if(mSrcPtrSize==4)
{
PX_ASSERT(sizeof(PxU32)==4);
const PxU32* data = reinterpret_cast<const PxU32*>(src);
PxU32 value = *data++;
src = reinterpret_cast<const char*>(data);
if(mPointerActiveRemap)
{
PxU32 ref;
if(mPointerActiveRemap->getObjectRef(value, ref))
{
value = ref;
}
else if(value)
{
// all pointers not in the pointer remap table get set as 0x12345678, this also applies to PhysX name properties (mName)
value=0x12345678;
}
}
else
{
//we should only get here during convertReferenceTables to build up the pointer map
PxU32 ref;
if (mPointerRemap.getObjectRef(value, ref))
{
value = ref;
}
else if(value)
{
const PxU32 remappedRef = 0x80000000 | (mPointerRemapCounter++ +1);
mPointerRemap.setObjectRef(value, remappedRef);
value = remappedRef;
}
}
if(mMustFlip)
flip(value);
if(mNullPtr)
value = 0;
*reinterpret_cast<PxU32*>(buffer) = value;
}
else
{
PX_ASSERT(mSrcPtrSize==8);
PX_ASSERT(sizeof(PxU64)==8);
const PxU64* data = reinterpret_cast<const PxU64*>(src);
PxU64 value = *data++;
src = reinterpret_cast<const char*>(data);
if(mPointerActiveRemap)
{
PxU32 ref;
if(mPointerActiveRemap->getObjectRef(value, ref))
{
value = ref;
}
else if(value)
{
// all pointers not in the pointer remap table get set as 0x12345678, this also applies to PhysX name properties (mName)
value=0x12345678;
}
}
else
{
//we should only get here during convertReferenceTables to build up the pointer map
PxU32 ref;
if (mPointerRemap.getObjectRef(value, ref))
{
value = ref;
}
else if(value)
{
const PxU32 remappedRef = 0x80000000 | (mPointerRemapCounter++ +1);
mPointerRemap.setObjectRef(value, remappedRef);
value = remappedRef;
}
}
if(mNullPtr)
value = 0;
testValue = value;
*reinterpret_cast<PxU64*>(buffer) = value;
}
if(mSrcPtrSize==mDstPtrSize)
{
const size_t size = mOutStream->write(buffer, PxU32(mSrcPtrSize));
PX_ASSERT(size==PxU32(mSrcPtrSize));
mOutputSize += int(size);
}
else
{
if(mDstPtrSize>mSrcPtrSize)
{
// 32bit to 64bit
PX_ASSERT(mDstPtrSize==8);
PX_ASSERT(mSrcPtrSize==4);
// We need to output the lower 32bits first for PC. Might be different on a 64bit console....
// Output src ptr for the lower 32bits
const size_t size = mOutStream->write(buffer, PxU32(mSrcPtrSize));
PX_ASSERT(size==PxU32(mSrcPtrSize));
mOutputSize += int(size);
// Output zeros for the higher 32bits
const int zero = 0;
const size_t size0 = mOutStream->write(&zero, 4);
PX_ASSERT(size0==4);
mOutputSize += int(size0);
}
else
{
// 64bit to 32bit
PX_ASSERT(mSrcPtrSize==8);
PX_ASSERT(mDstPtrSize==4);
// Not sure how we can safely convert 64bit ptrs to 32bit... just drop the high 32 bits?!?
PxU32 ptr32 = *reinterpret_cast<PxU32*>(buffer);
(void)ptr32;
PxU32 ptr32b = PxU32(testValue);
(void)ptr32b;
if(mMustFlip)
flip(ptr32b);
// Output src ptr for the lower 32bits
const size_t size = mOutStream->write(&ptr32b, 4);
PX_ASSERT(size==4);
mOutputSize += int(size);
}
}
}
}
void Sn::ConvX::convertHandle16(const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry)
{
(void)dstEntry;
if(mNoOutput)
return;
PX_ASSERT(strcmp(entry.mType, "PxU16") == 0);
PX_ASSERT(entry.mSize==dstEntry.mSize);
PX_ASSERT(mOutStream);
const PxU16* handles = reinterpret_cast<const PxU16*>(src);
for(int i=0;i<entry.mCount;i++)
{
PxU16 value = handles[i];
if (mHandle16ActiveRemap)
{
PxU16 ref;
bool isMapped = mHandle16ActiveRemap->getObjectRef(value, ref);
PX_UNUSED(isMapped);
PX_ASSERT(isMapped);
value = ref;
}
else
{
//we should only get here during convertReferenceTables to build up the pointer map
PxU16 ref;
if (mHandle16Remap.getObjectRef(value, ref))
{
value = ref;
}
else
{
const PxU16 remappedRef = mHandle16RemapCounter++;
mHandle16Remap.setObjectRef(value, remappedRef);
value = remappedRef;
}
}
if(mMustFlip)
flip(value);
const size_t size = mOutStream->write(&value, sizeof(PxU16));
PX_UNUSED(size);
PX_ASSERT(size==sizeof(PxU16));
mOutputSize += sizeof(PxU16);
}
}

View File

@ -0,0 +1,112 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
#ifndef PX_CONVX_OUTPUT_H
#define PX_CONVX_OUTPUT_H
#include "foundation/PxSimpleTypes.h"
namespace physx { namespace Sn {
struct PxMetaDataEntry;
class ConvX;
typedef void (Sn::ConvX::*ConvertCallback) (const char* src, const PxMetaDataEntry& entry, const PxMetaDataEntry& dstEntry);
inline_ void flip(PxI16& v)
{
PxI8* b = reinterpret_cast<PxI8*>(&v);
PxI8 temp = b[0];
b[0] = b[1];
b[1] = temp;
}
inline_ void flip(PxU16& v)
{
flip(reinterpret_cast<PxI16&>(v));
}
inline_ void flip32(PxI8* b)
{
PxI8 temp = b[0];
b[0] = b[3];
b[3] = temp;
temp = b[1];
b[1] = b[2];
b[2] = temp;
}
inline_ void flip(PxI32& v)
{
PxI8* b = reinterpret_cast<PxI8*>(&v);
flip32(b);
}
inline_ void flip(PxU32& v)
{
PxI8* b = reinterpret_cast<PxI8*>(&v);
flip32(b);
}
inline_ void flip(PxI64& v)
{
PxI8* b = reinterpret_cast<PxI8*>(&v);
PxI8 temp = b[0];
b[0] = b[7];
b[7] = temp;
temp = b[1];
b[1] = b[6];
b[6] = temp;
temp = b[2];
b[2] = b[5];
b[5] = temp;
temp = b[3];
b[3] = b[4];
b[4] = temp;
}
inline_ void flip(PxF32& v)
{
PxI8* b = reinterpret_cast<PxI8*>(&v);
flip32(b);
}
inline_ void flip(void*& v)
{
PxI8* b = reinterpret_cast<PxI8*>(&v);
flip32(b);
}
inline_ void flip(const PxI8*& v)
{
PxI8* b = const_cast<PxI8*>(v);
flip32(b);
}
} }
#endif

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-2021 NVIDIA Corporation. All rights reserved.
#include "SnConvX.h"
#include <assert.h>
using namespace physx;
void Sn::ConvX::resetUnions()
{
mUnions.clear();
}
bool Sn::ConvX::registerUnion(const char* name)
{
displayMessage(PxErrorCode::eDEBUG_INFO, "Registering union: %s\n", name);
Sn::Union u;
u.mName = name;
mUnions.pushBack(u);
return true;
}
bool Sn::ConvX::registerUnionType(const char* unionName, const char* typeName, int typeValue)
{
const PxU32 nb = mUnions.size();
for(PxU32 i=0;i<nb;i++)
{
if(strcmp(mUnions[i].mName, unionName)==0)
{
UnionType t;
t.mTypeName = typeName;
t.mTypeValue = typeValue;
mUnions[i].mTypes.pushBack(t);
displayMessage(PxErrorCode::eDEBUG_INFO, "Registering union type: %s | %s | %d\n", unionName, typeName, typeValue);
return true;
}
}
displayMessage(PxErrorCode::eINTERNAL_ERROR, "PxBinaryConverter: union not found: %s, please check the source metadata.\n", unionName);
return false;
}
const char* Sn::ConvX::getTypeName(const char* unionName, int typeValue)
{
const PxU32 nb = mUnions.size();
for(PxU32 i=0;i<nb;i++)
{
if(strcmp(mUnions[i].mName, unionName)==0)
{
const PxU32 nbTypes = mUnions[i].mTypes.size();
for(PxU32 j=0;j<nbTypes;j++)
{
const UnionType& t = mUnions[i].mTypes[j];
if(t.mTypeValue==typeValue)
return t.mTypeName;
}
break;
}
}
displayMessage(PxErrorCode::eINTERNAL_ERROR,
"PxBinaryConverter: union type not found: %s, type %d, please check the source metadata.\n", unionName, typeValue);
assert(0);
return NULL;
}

View File

@ -0,0 +1,45 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
#ifndef PX_UNION_H
#define PX_UNION_H
namespace physx { namespace Sn {
struct UnionType
{
const char* mTypeName;
int mTypeValue;
};
struct Union
{
const char* mName;
PsArray<UnionType> mTypes;
};
} }
#endif

View File

@ -0,0 +1,115 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "common/PxBase.h"
#include "SnSerializationContext.h"
#include "PsFoundation.h"
using namespace physx;
using namespace Sn;
PxBase* DeserializationContext::resolveReference(PxU32 kind, size_t reference) const
{
SerialObjectIndex objIndex;
if (kind == PX_SERIAL_REF_KIND_PXBASE)
{
const InternalPtrRefMap::Entry* entry0 = mInternalPtrReferencesMap.find(reference);
PX_ASSERT(entry0);
objIndex = entry0->second;
}
else if (kind == PX_SERIAL_REF_KIND_MATERIAL_IDX)
{
const InternalHandle16RefMap::Entry* entry0 = mInternalHandle16ReferencesMap.find(PxU16(reference));
PX_ASSERT(entry0);
objIndex = entry0->second;
}
else
{
return NULL;
}
bool isExternal;
PxU32 index = objIndex.getIndex(isExternal);
PxBase* base = NULL;
if (isExternal)
{
const ImportReference& entry = mImportReferences[index];
base = mExternalRefs->find(entry.id);
}
else
{
const ManifestEntry& entry = mManifestTable[index];
base = reinterpret_cast<PxBase*>(mObjectDataAddress + entry.offset);
}
PX_ASSERT(base);
return base;
}
void SerializationContext::registerReference(PxBase& serializable, PxU32 kind, size_t reference)
{
#if PX_CHECKED
if ((kind & PX_SERIAL_REF_KIND_PTR_TYPE_BIT) == 0 && reference > 0xffff)
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__, "PxSerializationContext::registerReference: only 16 bit handles supported.");
return;
}
#endif
bool isExternal = mExternalRefs && mExternalRefs->contains(serializable);
PxU32 index;
if (isExternal)
{
PxSerialObjectId id = mExternalRefs->getId(serializable);
PX_ASSERT(id != PX_SERIAL_OBJECT_ID_INVALID);
if (const Ps::HashMap<PxSerialObjectId, PxU32>::Entry* entry = mImportReferencesMap.find(id))
{
index = entry->second;
}
else
{
index = mImportReferences.size();
mImportReferencesMap.insert(id, index);
mImportReferences.pushBack(ImportReference(id, serializable.getConcreteType()));
}
}
else
{
PX_ASSERT(mCollection.contains(serializable));
index = mObjToCollectionIndexMap[&serializable];
}
if (kind & PX_SERIAL_REF_KIND_PXBASE)
{
mInternalPtrReferencesMap[reference] = SerialObjectIndex(index, isExternal);
}
else if (kind & PX_SERIAL_REF_KIND_MATERIAL_IDX)
{
mInternalHandle16ReferencesMap[PxU16(reference)] = SerialObjectIndex(index, isExternal);
}
}

View File

@ -0,0 +1,329 @@
//
// 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-2021 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_SN_SERIALIZATION_CONTEXT
#define PX_PHYSICS_SN_SERIALIZATION_CONTEXT
#include "foundation/PxAssert.h"
#include "foundation/PxMemory.h"
#include "common/PxSerialFramework.h"
#include "extensions/PxDefaultStreams.h"
#include "PsHash.h"
#include "PsUserAllocated.h"
#include "PsFoundation.h"
#include "CmPhysXCommon.h"
#include "CmCollection.h"
#include "CmUtils.h"
#include "SnConvX_Align.h"
namespace physx
{
namespace Sn
{
struct ManifestEntry
{
//= 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_FORCE_INLINE ManifestEntry(PxU32 _offset, PxType _type)
{
Cm::markSerializedMem(this, sizeof(ManifestEntry));
offset = _offset;
type = _type;
}
PX_FORCE_INLINE ManifestEntry() { Cm::markSerializedMem(this, sizeof(ManifestEntry)); }
PX_FORCE_INLINE void operator =(const ManifestEntry& m)
{
PxMemCopy(this, &m, sizeof(ManifestEntry));
}
PxU32 offset;
PxType type;
};
struct ImportReference
{
//= 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_FORCE_INLINE ImportReference(PxSerialObjectId _id, PxType _type)
{
Cm::markSerializedMem(this, sizeof(ImportReference));
id = _id;
type = _type;
}
PX_FORCE_INLINE ImportReference() { Cm::markSerializedMem(this, sizeof(ImportReference)); }
PX_FORCE_INLINE void operator =(const ImportReference& m)
{
PxMemCopy(this, &m, sizeof(ImportReference));
}
PxSerialObjectId id;
PxType type;
};
#define SERIAL_OBJECT_INDEX_TYPE_BIT (1u<<31)
struct SerialObjectIndex
{
//= 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_FORCE_INLINE SerialObjectIndex(PxU32 index, bool external) { setIndex(index, external); }
PX_FORCE_INLINE SerialObjectIndex(const SerialObjectIndex& objIndex) : mObjIndex(objIndex.mObjIndex) {}
PX_FORCE_INLINE SerialObjectIndex() : mObjIndex(PX_INVALID_U32) {}
PX_FORCE_INLINE void setIndex(PxU32 index, bool external)
{
PX_ASSERT((index & SERIAL_OBJECT_INDEX_TYPE_BIT) == 0);
mObjIndex = index | (external ? SERIAL_OBJECT_INDEX_TYPE_BIT : 0);
}
PX_FORCE_INLINE PxU32 getIndex(bool& isExternal)
{
PX_ASSERT(mObjIndex != PX_INVALID_U32);
isExternal = (mObjIndex & SERIAL_OBJECT_INDEX_TYPE_BIT) > 0;
return mObjIndex & ~SERIAL_OBJECT_INDEX_TYPE_BIT;
}
PX_FORCE_INLINE bool operator < (const SerialObjectIndex& so) const
{
return mObjIndex < so.mObjIndex;
}
private:
PxU32 mObjIndex;
};
struct ExportReference
{
//= 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_FORCE_INLINE ExportReference(PxSerialObjectId _id, SerialObjectIndex _objIndex)
{
Cm::markSerializedMem(this, sizeof(ExportReference));
id = _id;
objIndex = _objIndex;
}
PX_FORCE_INLINE ExportReference() { Cm::markSerializedMem(this, sizeof(ExportReference)); }
PX_FORCE_INLINE void operator =(const ExportReference& m)
{
PxMemCopy(this, &m, sizeof(ExportReference));
}
PxSerialObjectId id;
SerialObjectIndex objIndex;
};
struct InternalReferencePtr
{
//= 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_FORCE_INLINE InternalReferencePtr() {}
PX_FORCE_INLINE InternalReferencePtr(size_t _reference, SerialObjectIndex _objIndex) :
reference(_reference),
objIndex(_objIndex)
#if PX_P64_FAMILY
,pad(PX_PADDING_32)
#endif
{
}
size_t reference;
SerialObjectIndex objIndex;
#if PX_P64_FAMILY
PxU32 pad;
#endif
};
struct InternalReferenceHandle16
{
//= 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_FORCE_INLINE InternalReferenceHandle16() {}
PX_FORCE_INLINE InternalReferenceHandle16(PxU16 _reference, SerialObjectIndex _objIndex) :
reference(_reference),
pad(PX_PADDING_16),
objIndex(_objIndex)
{
}
PxU16 reference;
PxU16 pad;
SerialObjectIndex objIndex;
};
typedef Cm::CollectionHashMap<size_t, SerialObjectIndex> InternalPtrRefMap;
typedef Cm::CollectionHashMap<PxU16, SerialObjectIndex> InternalHandle16RefMap;
class DeserializationContext : public PxDeserializationContext, public Ps::UserAllocated
{
PX_NOCOPY(DeserializationContext)
public:
DeserializationContext(const ManifestEntry* manifestTable,
const ImportReference* importReferences,
PxU8* objectDataAddress,
const InternalPtrRefMap& internalPtrReferencesMap,
const InternalHandle16RefMap& internalHandle16ReferencesMap,
const Cm::Collection* externalRefs,
PxU8* extraData)
: mManifestTable(manifestTable)
, mImportReferences(importReferences)
, mObjectDataAddress(objectDataAddress)
, mInternalPtrReferencesMap(internalPtrReferencesMap)
, mInternalHandle16ReferencesMap(internalHandle16ReferencesMap)
, mExternalRefs(externalRefs)
{
mExtraDataAddress = extraData;
}
virtual PxBase* resolveReference(PxU32 kind, size_t reference) const;
private:
//various pointers to deserialized data
const ManifestEntry* mManifestTable;
const ImportReference* mImportReferences;
PxU8* mObjectDataAddress;
//internal references maps for resolving references.
const InternalPtrRefMap& mInternalPtrReferencesMap;
const InternalHandle16RefMap& mInternalHandle16ReferencesMap;
//external collection for resolving import references.
const Cm::Collection* mExternalRefs;
//const PxU32 mPhysXVersion;
};
class SerializationContext : public PxSerializationContext, public Ps::UserAllocated
{
PX_NOCOPY(SerializationContext)
public:
SerializationContext(const Cm::Collection& collection, const Cm::Collection* externalRefs)
: mCollection(collection)
, mExternalRefs(externalRefs)
{
// fill object to collection index map (same ordering as manifest)
for (PxU32 i=0;i<mCollection.internalGetNbObjects();i++)
{
mObjToCollectionIndexMap[mCollection.internalGetObject(i)] = i;
}
}
virtual void writeData(const void* buffer, PxU32 size) { mMemStream.write(buffer, size); }
virtual PxU32 getTotalStoredSize() { return mMemStream.getSize(); }
virtual void alignData(PxU32 alignment = PX_SERIAL_ALIGN)
{
if(!alignment)
return;
PxI32 bytesToPad = PxI32(getPadding(mMemStream.getSize(), alignment));
static const PxI32 BUFSIZE = 64;
char buf[BUFSIZE];
PxMemSet(buf, 0, bytesToPad < BUFSIZE ? PxU32(bytesToPad) : PxU32(BUFSIZE));
while(bytesToPad > 0)
{
mMemStream.write(buf, bytesToPad < BUFSIZE ? PxU32(bytesToPad) : PxU32(BUFSIZE));
bytesToPad -= BUFSIZE;
}
PX_ASSERT(!getPadding(getTotalStoredSize(), alignment));
}
virtual void writeName(const char*)
{
Ps::getFoundation().error(physx::PxErrorCode::eINVALID_OPERATION, __FILE__, __LINE__,
"Cannot export names during exportData.");
}
const PxCollection& getCollection() const { return mCollection; }
virtual void registerReference(PxBase& serializable, PxU32 kind, size_t reference);
const Ps::Array<ImportReference>& getImportReferences() { return mImportReferences; }
InternalPtrRefMap& getInternalPtrReferencesMap() { return mInternalPtrReferencesMap; }
InternalHandle16RefMap& getInternalHandle16ReferencesMap() { return mInternalHandle16ReferencesMap; }
PxU32 getSize() const { return mMemStream.getSize(); }
PxU8* getData() const { return mMemStream.getData(); }
private:
//import reference map for unique registration of import references and corresponding buffer.
Ps::HashMap<PxSerialObjectId, PxU32> mImportReferencesMap;
Ps::Array<ImportReference> mImportReferences;
//maps for unique registration of internal references
InternalPtrRefMap mInternalPtrReferencesMap;
InternalHandle16RefMap mInternalHandle16ReferencesMap;
//map for quick lookup of manifest index.
Ps::HashMap<const PxBase*, PxU32> mObjToCollectionIndexMap;
//collection and externalRefs collection for assigning references.
const Cm::Collection& mCollection;
const Cm::Collection* mExternalRefs;
PxDefaultMemoryOutputStream mMemStream;
};
} // namespace Sn
}
#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-2021 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 SN_FILE_H
#define SN_FILE_H
// fopen_s - returns 0 on success, non-zero on failure
#if PX_MICROSOFT_FAMILY
#include <stdio.h>
namespace physx
{
namespace sn
{
PX_INLINE PxI32 fopen_s(FILE** file, const char* name, const char* mode)
{
static const PxU32 MAX_LEN = 300;
char buf[MAX_LEN+1];
PxU32 i;
for(i = 0; i<MAX_LEN && name[i]; i++)
buf[i] = name[i] == '/' ? '\\' : name[i];
buf[i] = 0;
return i == MAX_LEN ? -1 : ::fopen_s(file, buf, mode);
};
} // namespace sn
} // namespace physx
#elif PX_UNIX_FAMILY || PX_PS4 || PX_SWITCH
#include <stdio.h>
namespace physx
{
namespace sn
{
PX_INLINE PxI32 fopen_s(FILE** file, const char* name, const char* mode)
{
FILE* fp = ::fopen(name, mode);
if(fp)
{
*file = fp;
return PxI32(0);
}
return -1;
}
} // namespace sn
} // namespace physx
#else
#error "Platform not supported!"
#endif
#endif //SN_FILE_H

View File

@ -0,0 +1,160 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "extensions/PxSerialization.h"
#include "PxPhysicsVersion.h"
#include "SnSerialUtils.h"
#include "PsString.h"
#include "PsBasicTemplates.h"
using namespace physx;
namespace
{
#define SN_NUM_BINARY_PLATFORMS 16
const PxU32 sBinaryPlatformTags[SN_NUM_BINARY_PLATFORMS] =
{
PX_MAKE_FOURCC('W','_','3','2'),
PX_MAKE_FOURCC('W','_','6','4'),
PX_MAKE_FOURCC('L','_','3','2'),
PX_MAKE_FOURCC('L','_','6','4'),
PX_MAKE_FOURCC('M','_','3','2'),
PX_MAKE_FOURCC('M','_','6','4'),
PX_MAKE_FOURCC('M','O','C','A'),
PX_MAKE_FOURCC('A','N','D','R'),
PX_MAKE_FOURCC('A','I','O','S'),
PX_MAKE_FOURCC('A','A','6','4'),
PX_MAKE_FOURCC('X','O','N','E'),
PX_MAKE_FOURCC('N','X','3','2'),
PX_MAKE_FOURCC('N','X','6','4'),
PX_MAKE_FOURCC('L','A','6','4'),
PX_MAKE_FOURCC('W','A','3','2'),
PX_MAKE_FOURCC('W','A','6','4'),
};
const char* sBinaryPlatformNames[SN_NUM_BINARY_PLATFORMS] =
{
"win32",
"win64",
"linux32",
"linux64",
"mac32",
"mac64",
"ps4",
"android",
"ios",
"ios64",
"xboxone",
"switch32",
"switch64",
"linuxaarch64",
"uwparm",
"uwparm64",
};
}
namespace physx { namespace Sn {
PxU32 getBinaryPlatformTag()
{
#if PX_WINDOWS && PX_X86
return sBinaryPlatformTags[0];
#elif PX_WINDOWS && PX_X64
return sBinaryPlatformTags[1];
#elif PX_LINUX && PX_X86
return sBinaryPlatformTags[2];
#elif PX_LINUX && PX_X64
return sBinaryPlatformTags[3];
#elif PX_OSX && PX_X86
return sBinaryPlatformTags[4];
#elif PX_OSX && PX_X64
return sBinaryPlatformTags[5];
#elif PX_PS4
return sBinaryPlatformTags[6];
#elif PX_ANDROID
return sBinaryPlatformTags[7];
#elif PX_IOS && PX_ARM
return sBinaryPlatformTags[8];
#elif PX_IOS && PX_A64
return sBinaryPlatformTags[9];
#elif PX_XBOXONE || PX_XBOX_SERIES_X
return sBinaryPlatformTags[10];
#elif PX_SWITCH && !PX_A64
return sBinaryPlatformTags[11];
#elif PX_SWITCH && PX_A64
return sBinaryPlatformTags[12];
#elif PX_LINUX && PX_A64
return sBinaryPlatformTags[13];
#elif PX_UWP && PX_ARM
return sBinaryPlatformTags[14];
#elif PX_UWP && PX_A64
return sBinaryPlatformTags[15];
#else
#error Unknown binary platform
#endif
}
bool isBinaryPlatformTagValid(physx::PxU32 platformTag)
{
PxU32 platformIndex = 0;
while (platformIndex < SN_NUM_BINARY_PLATFORMS && platformTag != sBinaryPlatformTags[platformIndex]) platformIndex++;
return platformIndex < SN_NUM_BINARY_PLATFORMS;
}
const char* getBinaryPlatformName(physx::PxU32 platformTag)
{
PxU32 platformIndex = 0;
while (platformIndex < SN_NUM_BINARY_PLATFORMS && platformTag != sBinaryPlatformTags[platformIndex]) platformIndex++;
return (platformIndex == SN_NUM_BINARY_PLATFORMS) ? "unknown" : sBinaryPlatformNames[platformIndex];
}
const char* getBinaryVersionGuid()
{
PX_COMPILE_TIME_ASSERT(sizeof(PX_BINARY_SERIAL_VERSION) == SN_BINARY_VERSION_GUID_NUM_CHARS + 1);
return PX_BINARY_SERIAL_VERSION;
}
bool checkCompatibility(const char* binaryVersionGuidCandidate)
{
for(PxU32 i=0; i<SN_BINARY_VERSION_GUID_NUM_CHARS; i++)
{
if (binaryVersionGuidCandidate[i] != PX_BINARY_SERIAL_VERSION[i])
{
return false;
}
}
return true;
}
} // Sn
} // physx

View File

@ -0,0 +1,52 @@
//
// 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-2021 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_SN_SERIAL_UTILS
#define PX_PHYSICS_SN_SERIAL_UTILS
#include "CmPhysXCommon.h"
#define SN_BINARY_VERSION_GUID_NUM_CHARS 32
namespace physx
{
namespace Sn
{
PxU32 getBinaryPlatformTag();
bool isBinaryPlatformTagValid(PxU32 platformTag);
const char* getBinaryPlatformName(PxU32 platformTag);
const char* getBinaryVersionGuid();
bool checkCompatibility(const char* binaryVersionGuidCandidate);
}
}
#endif

View File

@ -0,0 +1,420 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "common/PxMetaData.h"
#include "common/PxSerializer.h"
#include "extensions/PxConstraintExt.h"
#include "PxPhysicsAPI.h"
#include "PxPhysicsVersion.h"
#include "PsFoundation.h"
#include "SnConvX.h"
#include "SnSerializationRegistry.h"
#include "SnSerialUtils.h"
#include "ExtSerialization.h"
#include "CmCollection.h"
using namespace physx;
using namespace Sn;
namespace
{
struct RequiresCallback : public PxProcessPxBaseCallback
{
RequiresCallback(physx::PxCollection& c) : collection(c) {}
void process(PxBase& base)
{
if(!collection.contains(base))
collection.add(base);
}
PxCollection& collection;
PX_NOCOPY(RequiresCallback)
};
struct CompleteCallback : public PxProcessPxBaseCallback
{
CompleteCallback(physx::PxCollection& r, physx::PxCollection& c, const physx::PxCollection* e) :
required(r), complete(c), external(e) {}
void process(PxBase& base)
{
if(complete.contains(base) || (external && external->contains(base)))
return;
if(!required.contains(base))
required.add(base);
}
PxCollection& required;
PxCollection& complete;
const PxCollection* external;
PX_NOCOPY(CompleteCallback)
};
void getRequiresCollection(PxCollection& required, PxCollection& collection, PxCollection& complete, const PxCollection* external, PxSerializationRegistry& sr, bool followJoints)
{
CompleteCallback callback(required, complete, external);
for (PxU32 i = 0; i < collection.getNbObjects(); ++i)
{
PxBase& s = collection.getObject(i);
const PxSerializer* serializer = sr.getSerializer(s.getConcreteType());
PX_ASSERT(serializer);
serializer->requiresObjects(s, callback);
if(followJoints)
{
PxRigidActor* actor = s.is<PxRigidActor>();
if(actor)
{
Ps::Array<PxConstraint*> objects(actor->getNbConstraints());
actor->getConstraints(objects.begin(), objects.size());
for(PxU32 j=0;j<objects.size();j++)
{
PxU32 typeId;
PxJoint* joint = reinterpret_cast<PxJoint*>(objects[j]->getExternalReference(typeId));
if(typeId == PxConstraintExtIDs::eJOINT)
{
const PxSerializer* sj = sr.getSerializer(joint->getConcreteType());
PX_ASSERT(sj);
sj->requiresObjects(*joint, callback);
if(!required.contains(*joint))
required.add(*joint);
}
}
}
}
}
}
}
bool PxSerialization::isSerializable(PxCollection& collection, PxSerializationRegistry& sr, const PxCollection* externalReferences)
{
PxCollection* subordinateCollection = PxCreateCollection();
PX_ASSERT(subordinateCollection);
for(PxU32 i = 0; i < collection.getNbObjects(); ++i)
{
PxBase& s = collection.getObject(i);
const PxSerializer* serializer = sr.getSerializer(s.getConcreteType());
PX_ASSERT(serializer);
if(serializer->isSubordinate())
subordinateCollection->add(s);
if(externalReferences)
{
PxSerialObjectId id = collection.getId(s);
if(id != PX_SERIAL_OBJECT_ID_INVALID)
{
PxBase* object = externalReferences->find(id);
if(object && (object != &s))
{
subordinateCollection->release();
Ps::getFoundation().error(physx::PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"PxSerialization::isSerializable: Reference id %" PX_PRIu64 " used both in current collection and in externalReferences. "
"Please use unique identifiers.", id);
return false;
}
}
}
}
PxCollection* requiresCollection = PxCreateCollection();
PX_ASSERT(requiresCollection);
RequiresCallback requiresCallback0(*requiresCollection);
for (PxU32 i = 0; i < collection.getNbObjects(); ++i)
{
PxBase& s = collection.getObject(i);
const PxSerializer* serializer = sr.getSerializer(s.getConcreteType());
PX_ASSERT(serializer);
serializer->requiresObjects(s, requiresCallback0);
Cm::Collection* cmRequiresCollection = static_cast<Cm::Collection*>(requiresCollection);
for(PxU32 j = 0; j < cmRequiresCollection->getNbObjects(); ++j)
{
PxBase& s0 = cmRequiresCollection->getObject(j);
if(subordinateCollection->contains(s0))
{
subordinateCollection->remove(s0);
continue;
}
bool requiredIsInCollection = collection.contains(s0);
if(!requiredIsInCollection)
{
if(externalReferences)
{
if(!externalReferences->contains(s0))
{
Ps::getFoundation().error(physx::PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"PxSerialization::isSerializable: Object of type %s references a missing object of type %s. "
"The missing object needs to be added to either the current collection or the externalReferences collection.",
s.getConcreteTypeName(), s0.getConcreteTypeName());
}
else if(externalReferences->getId(s0) == PX_SERIAL_OBJECT_ID_INVALID)
{
Ps::getFoundation().error(physx::PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"PxSerialization::isSerializable: Object of type %s in externalReferences collection requires an id.",
s0.getConcreteTypeName());
}
else
continue;
}
else
{
Ps::getFoundation().error(physx::PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"PxSerialization::isSerializable: Object of type %s references a missing serial object of type %s. "
"Please completed the collection or specify an externalReferences collection containing the object.",
s.getConcreteTypeName(), s0.getConcreteTypeName());
}
subordinateCollection->release();
requiresCollection->release();
return false;
}
}
cmRequiresCollection->mObjects.clear();
}
requiresCollection->release();
PxU32 numOrphans = subordinateCollection->getNbObjects();
for(PxU32 j = 0; j < numOrphans; ++j)
{
PxBase& subordinate = subordinateCollection->getObject(j);
Ps::getFoundation().error(physx::PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"PxSerialization::isSerializable: An object of type %s is subordinate but not required "
"by other objects in the collection (orphan). Please remove the object from the collection or add its owner.",
subordinate.getConcreteTypeName());
}
subordinateCollection->release();
if(numOrphans>0)
return false;
if(externalReferences)
{
PxCollection* oppositeRequiresCollection = PxCreateCollection();
PX_ASSERT(oppositeRequiresCollection);
RequiresCallback requiresCallback(*oppositeRequiresCollection);
for (PxU32 i = 0; i < externalReferences->getNbObjects(); ++i)
{
PxBase& s = externalReferences->getObject(i);
const PxSerializer* serializer = sr.getSerializer(s.getConcreteType());
PX_ASSERT(serializer);
serializer->requiresObjects(s, requiresCallback);
Cm::Collection* cmCollection = static_cast<Cm::Collection*>(oppositeRequiresCollection);
for(PxU32 j = 0; j < cmCollection->getNbObjects(); ++j)
{
PxBase& s0 = cmCollection->getObject(j);
if(collection.contains(s0))
{
oppositeRequiresCollection->release();
Ps::getFoundation().error(physx::PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"PxSerialization::isSerializable: Object of type %s in externalReferences references an object "
"of type %s in collection (circular dependency).",
s.getConcreteTypeName(), s0.getConcreteTypeName());
return false;
}
}
cmCollection->mObjects.clear();
}
oppositeRequiresCollection->release();
}
return true;
}
void PxSerialization::complete(PxCollection& collection, PxSerializationRegistry& sr, const PxCollection* exceptFor, bool followJoints)
{
PxCollection* curCollection = PxCreateCollection();
PX_ASSERT(curCollection);
curCollection->add(collection);
PxCollection* requiresCollection = PxCreateCollection();
PX_ASSERT(requiresCollection);
do
{
getRequiresCollection(*requiresCollection, *curCollection, collection, exceptFor, sr, followJoints);
collection.add(*requiresCollection);
PxCollection* swap = curCollection;
curCollection = requiresCollection;
requiresCollection = swap;
(static_cast<Cm::Collection*>(requiresCollection))->mObjects.clear();
}while(curCollection->getNbObjects() > 0);
requiresCollection->release();
curCollection->release();
}
void PxSerialization::createSerialObjectIds(PxCollection& collection, const PxSerialObjectId base)
{
PxSerialObjectId localBase = base;
PxU32 nbObjects = collection.getNbObjects();
for (PxU32 i = 0; i < nbObjects; ++i)
{
while(collection.find(localBase))
{
localBase++;
}
PxBase& s = collection.getObject(i);
if(PX_SERIAL_OBJECT_ID_INVALID == collection.getId(s))
{
collection.addId(s, localBase);
localBase++;
}
}
}
namespace physx { namespace Sn
{
static PxU32 addToStringTable(physx::shdfnd::Array<char>& stringTable, const char* str)
{
if(!str)
return 0xffffffff;
PxI32 length = PxI32(stringTable.size());
const char* table = stringTable.begin();
const char* start = table;
while(length)
{
if(strcmp(table, str)==0)
return PxU32(table - start);
const char* saved = table;
while(*table++);
length -= PxU32(table - saved);
PX_ASSERT(length>=0);
}
const PxU32 offset = stringTable.size();
while(*str)
stringTable.pushBack(*str++);
stringTable.pushBack(0);
return offset;
}
} }
void PxSerialization::dumpBinaryMetaData(PxOutputStream& outputStream, PxSerializationRegistry& sr)
{
class MetaDataStream : public PxOutputStream
{
public:
bool addNewType(const char* typeName)
{
for(PxU32 i=0;i<types.size();i++)
{
if(strcmp(types[i], typeName)==0)
return false;
}
types.pushBack(typeName);
return true;
}
virtual PxU32 write(const void* src, PxU32 count)
{
PX_ASSERT(count==sizeof(PxMetaDataEntry));
const PxMetaDataEntry* entry = reinterpret_cast<const PxMetaDataEntry*>(src);
if(( entry->flags & PxMetaDataFlag::eTYPEDEF) || ((entry->flags & PxMetaDataFlag::eCLASS) && (!entry->name)) )
newType = addNewType(entry->type);
if(newType)
metaData.pushBack(*entry);
return count;
}
shdfnd::Array<PxMetaDataEntry> metaData;
shdfnd::Array<const char*> types;
bool newType;
}s;
SerializationRegistry& sn = static_cast<SerializationRegistry&>(sr);
sn.getBinaryMetaData(s);
shdfnd::Array<char> stringTable;
PxU32 nb = s.metaData.size();
PxMetaDataEntry* entries = s.metaData.begin();
for(PxU32 i=0;i<nb;i++)
{
entries[i].type = reinterpret_cast<const char*>(size_t(addToStringTable(stringTable, entries[i].type)));
entries[i].name = reinterpret_cast<const char*>(size_t(addToStringTable(stringTable, entries[i].name)));
}
PxU32 platformTag = getBinaryPlatformTag();
const PxU32 gaussMapLimit = 32;
const PxU32 header = PX_MAKE_FOURCC('M','E','T','A');
const PxU32 version = PX_PHYSICS_VERSION;
const PxU32 ptrSize = sizeof(void*);
outputStream.write(&header, 4);
outputStream.write(&version, 4);
outputStream.write(PX_BINARY_SERIAL_VERSION, SN_BINARY_VERSION_GUID_NUM_CHARS);
outputStream.write(&ptrSize, 4);
outputStream.write(&platformTag, 4);
outputStream.write(&gaussMapLimit, 4);
outputStream.write(&nb, 4);
outputStream.write(entries, nb*sizeof(PxMetaDataEntry));
//concreteTypes to name
PxU32 num = sn.getNbSerializers();
outputStream.write(&num, 4);
for(PxU32 i=0; i<num; i++)
{
PxU16 type = sn.getSerializerType(i);
PxU32 nameOffset = addToStringTable(stringTable, sn.getSerializerName(i));
outputStream.write(&type, 2);
outputStream.write(&nameOffset, 4);
}
PxU32 length = stringTable.size();
const char* table = stringTable.begin();
outputStream.write(&length, 4);
outputStream.write(table, length);
}
PxBinaryConverter* PxSerialization::createBinaryConverter()
{
return PX_NEW(ConvX)();
}

View File

@ -0,0 +1,288 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "common/PxSerializer.h"
#include "PxPhysics.h"
#include "PxPhysicsSerialization.h"
#include "PxArticulationLink.h"
#include "SnSerializationRegistry.h"
#include "ExtSerialization.h"
#include "CmCollection.h"
#include "PsFoundation.h"
#include "PsString.h"
using namespace physx;
namespace
{
class CollectionSorter : public PxProcessPxBaseCallback
{
typedef Ps::Pair<PxBase*, PxSerialObjectId> Object;
class Element
{
public:
Object object;
Ps::Array<PxU32> children;
bool isFinished;
Element(PxBase* obj = NULL) : object(obj, PX_SERIAL_OBJECT_ID_INVALID), isFinished(false) {}
};
public:
CollectionSorter(Cm::Collection& collection, Sn::SerializationRegistry& sr, bool isRepx) : mCollection(collection), mSr(sr), mIsRepx(isRepx) {}
virtual ~CollectionSorter(){}
void process(PxBase& base)
{
addChild(&base);
//ArticulationLink is not a repx serializer, so should require Articulation here
if( mIsRepx && PxConcreteType::eARTICULATION_LINK == base.getConcreteType() )
{
PxArticulationLink* link = static_cast<PxArticulationLink*>(&base);
PxBase* a = reinterpret_cast<PxBase*>(&link->getArticulation());
if(mCurElement->object.first != a ) //don't require itself
addChild(a);
}
}
void sort()
{
Element element;
PxU32 i;
PxU32 nbObject = mCollection.internalGetNbObjects();
const Cm::Collection::ObjectToIdMap::Entry* objectdatas = mCollection.internalGetObjects();
for( i = 0; i < nbObject; ++i )
{
element.object.first = objectdatas[i].first;
element.object.second = objectdatas[i].second;
mObjToIdMap.insert(objectdatas[i].first, mElements.size());
mElements.pushBack(element);
}
for( i = 0; i < nbObject; ++i )
{
mCurElement = &mElements[i];
const PxSerializer* serializer = mSr.getSerializer(mCurElement->object.first->getConcreteType());
PX_ASSERT(serializer);
serializer->requiresObjects(*mCurElement->object.first, *this);
}
for( i = 0; i < nbObject; ++i )
{
if( mElements[i].isFinished )
continue;
AddElement(mElements[i]);
}
mCollection.mObjects.clear();
for(Ps::Array<Object>::Iterator o = mSorted.begin(); o != mSorted.end(); ++o )
{
mCollection.internalAdd(o->first, o->second);
}
}
void AddElement(Element& e)
{
if( !e.isFinished )
{
for( Ps::Array<PxU32>::Iterator child = e.children.begin(); child != e.children.end(); ++child )
{
AddElement(mElements[*child]);
}
mSorted.pushBack(e.object);
e.isFinished = true;
}
}
private:
PX_INLINE void addChild(PxBase* base)
{
PX_ASSERT(mCurElement);
const Ps::HashMap<PxBase*, PxU32>::Entry* entry = mObjToIdMap.find(base);
if(entry)
mCurElement->children.pushBack(entry->second);
}
CollectionSorter& operator=(const CollectionSorter&);
Ps::HashMap<PxBase*, PxU32> mObjToIdMap;
Ps::Array<Element> mElements;
Cm::Collection& mCollection;
Sn::SerializationRegistry& mSr;
Ps::Array<Object> mSorted;
Element* mCurElement;
bool mIsRepx;
};
}
namespace physx { namespace Sn {
SerializationRegistry::SerializationRegistry(PxPhysics& physics)
: mPhysics(physics)
{
PxRegisterPhysicsSerializers(*this);
Ext::RegisterExtensionsSerializers(*this);
registerBinaryMetaDataCallback(PxGetPhysicsBinaryMetaData);
registerBinaryMetaDataCallback(Ext::GetExtensionsBinaryMetaData);
}
SerializationRegistry::~SerializationRegistry()
{
PxUnregisterPhysicsSerializers(*this);
Ext::UnregisterExtensionsSerializers(*this);
if(mSerializers.size() > 0)
{
shdfnd::getFoundation().error(physx::PxErrorCode::eDEBUG_WARNING, __FILE__, __LINE__,
"PxSerializationRegistry::release(): some registered PxSerializer instances were not unregistered");
}
if(mRepXSerializers.size() > 0)
{
shdfnd::getFoundation().error(physx::PxErrorCode::eDEBUG_WARNING, __FILE__, __LINE__,
"PxSerializationRegistry::release(): some registered PxRepXSerializer instances were not unregistered");
}
}
void SerializationRegistry::registerSerializer(PxType type, PxSerializer& serializer)
{
if(mSerializers.find(type))
{
shdfnd::getFoundation().error(physx::PxErrorCode::eDEBUG_WARNING, __FILE__, __LINE__,
"PxSerializationRegistry::registerSerializer: Type %d has already been registered", type);
}
mSerializers.insert(type, &serializer);
}
PxSerializer* SerializationRegistry::unregisterSerializer(PxType type)
{
const SerializerMap::Entry* e = mSerializers.find(type);
PxSerializer* s = e ? e->second : NULL;
if(!mSerializers.erase(type))
{
shdfnd::getFoundation().error(physx::PxErrorCode::eDEBUG_WARNING, __FILE__, __LINE__,
"PxSerializationRegistry::unregisterSerializer: failed to find PxSerializer instance for type %d", type);
}
return s;
}
const PxSerializer* SerializationRegistry::getSerializer(PxType type) const
{
const SerializerMap::Entry* e = mSerializers.find(type);
#if PX_CHECKED
if (!e)
{
shdfnd::getFoundation().error(physx::PxErrorCode::eDEBUG_WARNING, __FILE__, __LINE__,
"PxSerializationRegistry::getSerializer: failed to find PxSerializer instance for type %d", type);
}
#endif
return e ? e->second : NULL;
}
PxType SerializationRegistry::getSerializerType(PxU32 index) const
{
PX_ASSERT(index < mSerializers.size());
return mSerializers.getEntries()[index].first;
}
const char* SerializationRegistry::getSerializerName(PxU32 index) const
{
PX_ASSERT(index < mSerializers.size());
return mSerializers.getEntries()[index].second->getConcreteTypeName();
}
void SerializationRegistry::registerBinaryMetaDataCallback(PxBinaryMetaDataCallback callback)
{
mMetaDataCallbacks.pushBack(callback);
}
void SerializationRegistry::getBinaryMetaData(PxOutputStream& stream) const
{
for(PxU32 i = 0; i < mMetaDataCallbacks.size(); i++)
{
mMetaDataCallbacks[i](stream);
}
}
void SerializationRegistry::registerRepXSerializer(PxType type, PxRepXSerializer& serializer)
{
if(mRepXSerializers.find(type))
{
shdfnd::getFoundation().error(physx::PxErrorCode::eDEBUG_WARNING, __FILE__, __LINE__,
"PxSerializationRegistry::registerRepXSerializer: Type %d has already been registered", type);
}
mRepXSerializers.insert(type, &serializer);
}
PxRepXSerializer* SerializationRegistry::getRepXSerializer(const char* typeName) const
{
SerializationRegistry* sr = const_cast<SerializationRegistry*>(this);
for( RepXSerializerMap::Iterator iter = sr->mRepXSerializers.getIterator(); !iter.done(); ++iter)
{
if ( physx::shdfnd::stricmp( iter->second->getTypeName(), typeName ) == 0 )
return iter->second;
}
return NULL;
}
PxRepXSerializer* SerializationRegistry::unregisterRepXSerializer(PxType type)
{
const RepXSerializerMap::Entry* e = mRepXSerializers.find(type);
PxRepXSerializer* s = e ? e->second : NULL;
if(!mRepXSerializers.erase(type))
{
shdfnd::getFoundation().error(physx::PxErrorCode::eDEBUG_WARNING, __FILE__, __LINE__,
"PxSerializationRegistry::unregisterRepXSerializer: failed to find PxRepXSerializer instance for type %d", type);
}
return s;
}
void sortCollection(Cm::Collection& collection, SerializationRegistry& sr, bool isRepx)
{
CollectionSorter sorter(collection, sr, isRepx);
sorter.sort();
}
} // Sn
PxSerializationRegistry* PxSerialization::createSerializationRegistry(PxPhysics& physics)
{
return PX_NEW(Sn::SerializationRegistry)(physics);
}
} // physx

View File

@ -0,0 +1,92 @@
//
// 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-2021 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_SN_SERIALIZATION_REGISTRY
#define PX_PHYSICS_SN_SERIALIZATION_REGISTRY
#include "extensions/PxSerialization.h"
#include "extensions/PxRepXSerializer.h"
#include "CmPhysXCommon.h"
#include "PsUserAllocated.h"
#include "PsArray.h"
#include "PsHashMap.h"
namespace physx
{
namespace Cm { class Collection; }
namespace Sn {
class SerializationRegistry : public PxSerializationRegistry, public Ps::UserAllocated
{
public:
SerializationRegistry(PxPhysics& physics);
virtual ~SerializationRegistry();
virtual void release(){ PX_DELETE(this); }
PxPhysics& getPhysics() const { return mPhysics; }
//binary
void registerSerializer(PxType type, PxSerializer& serializer);
PxSerializer* unregisterSerializer(PxType type);
void registerBinaryMetaDataCallback(PxBinaryMetaDataCallback callback);
void getBinaryMetaData(PxOutputStream& stream) const;
const PxSerializer* getSerializer(PxType type) const;
const char* getSerializerName(PxU32 index) const;
PxType getSerializerType(PxU32 index) const;
PxU32 getNbSerializers() const { return mSerializers.size(); }
//repx
void registerRepXSerializer(PxType type, PxRepXSerializer& serializer);
PxRepXSerializer* getRepXSerializer(const char* typeName) const;
PxRepXSerializer* unregisterRepXSerializer(PxType type);
protected:
SerializationRegistry &operator=(const SerializationRegistry &);
private:
typedef Ps::CoalescedHashMap<PxType, PxSerializer*> SerializerMap;
typedef Ps::HashMap<PxType, PxRepXSerializer*> RepXSerializerMap;
PxPhysics& mPhysics;
SerializerMap mSerializers;
RepXSerializerMap mRepXSerializers;
Ps::Array<PxBinaryMetaDataCallback> mMetaDataCallbacks;
};
void sortCollection(Cm::Collection& collection, SerializationRegistry& sr, bool isRepx);
} // Sn
} // physx
#endif

View File

@ -0,0 +1,145 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "PxMetaDataObjects.h"
#include "PxExtensionMetaDataObjects.h"
#include "ExtJointMetaDataExtensions.h"
#include "SnJointRepXSerializer.h"
namespace physx {
template<typename TJointType>
inline TJointType* createJoint( PxPhysics& physics,
PxRigidActor* actor0, const PxTransform& localFrame0,
PxRigidActor* actor1, const PxTransform& localFrame1 )
{
PX_UNUSED(physics);
PX_UNUSED(actor0);
PX_UNUSED(actor1);
PX_UNUSED(localFrame0);
PX_UNUSED(localFrame1);
return NULL;
}
template<>
inline PxD6Joint* createJoint<PxD6Joint>(PxPhysics& physics,
PxRigidActor* actor0, const PxTransform& localFrame0,
PxRigidActor* actor1, const PxTransform& localFrame1)
{
return PxD6JointCreate( physics, actor0, localFrame0, actor1, localFrame1 );
}
template<>
inline PxDistanceJoint* createJoint<PxDistanceJoint>(PxPhysics& physics,
PxRigidActor* actor0, const PxTransform& localFrame0,
PxRigidActor* actor1, const PxTransform& localFrame1)
{
return PxDistanceJointCreate( physics, actor0, localFrame0, actor1, localFrame1 );
}
template<>
inline PxContactJoint* createJoint<PxContactJoint>(PxPhysics& physics,
PxRigidActor* actor0, const PxTransform& localFrame0,
PxRigidActor* actor1, const PxTransform& localFrame1)
{
return PxContactJointCreate( physics, actor0, localFrame0, actor1, localFrame1 );
}
template<>
inline PxFixedJoint* createJoint<PxFixedJoint>(PxPhysics& physics,
PxRigidActor* actor0, const PxTransform& localFrame0,
PxRigidActor* actor1, const PxTransform& localFrame1)
{
return PxFixedJointCreate( physics, actor0, localFrame0, actor1, localFrame1 );
}
template<>
inline PxPrismaticJoint* createJoint<PxPrismaticJoint>(PxPhysics& physics,
PxRigidActor* actor0, const PxTransform& localFrame0,
PxRigidActor* actor1, const PxTransform& localFrame1)
{
return PxPrismaticJointCreate( physics, actor0, localFrame0, actor1, localFrame1 );
}
template<>
inline PxRevoluteJoint* createJoint<PxRevoluteJoint>(PxPhysics& physics,
PxRigidActor* actor0, const PxTransform& localFrame0,
PxRigidActor* actor1, const PxTransform& localFrame1)
{
return PxRevoluteJointCreate( physics, actor0, localFrame0, actor1, localFrame1 );
}
template<>
inline PxSphericalJoint* createJoint<PxSphericalJoint>(PxPhysics& physics,
PxRigidActor* actor0, const PxTransform& localFrame0,
PxRigidActor* actor1, const PxTransform& localFrame1)
{
return PxSphericalJointCreate( physics, actor0, localFrame0, actor1, localFrame1 );
}
template<typename TJointType>
PxRepXObject PxJointRepXSerializer<TJointType>::fileToObject( XmlReader& inReader, XmlMemoryAllocator& inAllocator, PxRepXInstantiationArgs& inArgs, PxCollection* inCollection )
{
PxRigidActor* actor0 = NULL;
PxRigidActor* actor1 = NULL;
PxTransform localPose0 = PxTransform(PxIdentity);
PxTransform localPose1 = PxTransform(PxIdentity);
bool ok = true;
if ( inReader.gotoChild( "Actors" ) )
{
ok = readReference<PxRigidActor>( inReader, *inCollection, "actor0", actor0 );
ok &= readReference<PxRigidActor>( inReader, *inCollection, "actor1", actor1 );
inReader.leaveChild();
}
TJointType* theJoint = !ok ? NULL : createJoint<TJointType>( inArgs.physics, actor0, localPose0, actor1, localPose1 );
if ( theJoint )
{
PxConstraint* constraint = theJoint->getConstraint();
PX_ASSERT( constraint );
inCollection->add( *constraint );
this->fileToObjectImpl( theJoint, inReader, inAllocator, inArgs, inCollection );
}
return PxCreateRepXObject(theJoint);
}
template<typename TJointType>
void PxJointRepXSerializer<TJointType>::objectToFileImpl( const TJointType* inObj, PxCollection* inCollection, XmlWriter& inWriter, MemoryBuffer& inTempBuffer, PxRepXInstantiationArgs& )
{
writeAllProperties( inObj, inWriter, inTempBuffer, *inCollection );
}
// explicit template instantiations
template struct PxJointRepXSerializer<PxFixedJoint>;
template struct PxJointRepXSerializer<PxDistanceJoint>;
template struct PxJointRepXSerializer<PxContactJoint>;
template struct PxJointRepXSerializer<PxD6Joint>;
template struct PxJointRepXSerializer<PxPrismaticJoint>;
template struct PxJointRepXSerializer<PxRevoluteJoint>;
template struct PxJointRepXSerializer<PxSphericalJoint>;
}

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-2021 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 SN_JOINT_REPX_SERIALIZER_H
#define SN_JOINT_REPX_SERIALIZER_H
/** \addtogroup RepXSerializers
@{
*/
#include "extensions/PxRepXSimpleType.h"
#include "SnRepXSerializerImpl.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class XmlReader;
class XmlMemoryAllocator;
class XmlWriter;
class MemoryBuffer;
template<typename TJointType>
struct PxJointRepXSerializer : public RepXSerializerImpl<TJointType>
{
PxJointRepXSerializer(PxAllocatorCallback& inAllocator) : RepXSerializerImpl<TJointType>(inAllocator) {}
virtual PxRepXObject fileToObject(XmlReader& inReader, XmlMemoryAllocator& inAllocator, PxRepXInstantiationArgs& inArgs, PxCollection* inCollection);
virtual void objectToFileImpl(const TJointType* inObj, PxCollection* inCollection, XmlWriter& inWriter, MemoryBuffer& inTempBuffer, PxRepXInstantiationArgs&);
virtual TJointType* allocateObject(PxRepXInstantiationArgs&) { return NULL; }
};
#if PX_SUPPORT_EXTERN_TEMPLATE
// explicit template instantiations declarations
extern template struct PxJointRepXSerializer<PxD6Joint>;
extern template struct PxJointRepXSerializer<PxDistanceJoint>;
extern template struct PxJointRepXSerializer<PxContactJoint>;
extern template struct PxJointRepXSerializer<PxFixedJoint>;
extern template struct PxJointRepXSerializer<PxPrismaticJoint>;
extern template struct PxJointRepXSerializer<PxRevoluteJoint>;
extern template struct PxJointRepXSerializer<PxSphericalJoint>;
#endif
#if !PX_DOXYGEN
} // namespace physx
#endif
/** @} */
#endif

View File

@ -0,0 +1,134 @@
//
// 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-2021 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_PXSTREAMOPERATORS_H
#define PX_PXSTREAMOPERATORS_H
#include "foundation/PxVec3.h"
#include "foundation/PxTransform.h"
#include "foundation/PxBounds3.h"
#include "PxFiltering.h"
#include "PsString.h"
namespace physx
{
static inline PxU32 strLenght( const char* inStr )
{
return inStr ? PxU32(strlen(inStr)) : 0;
}
}
namespace physx // ADL requires we put the operators in the same namespace as the underlying type of PxOutputStream
{
inline PxOutputStream& operator << ( PxOutputStream& ioStream, const char* inString )
{
if ( inString && *inString )
{
ioStream.write( inString, PxU32(strlen(inString)) );
}
return ioStream;
}
template<typename TDataType>
inline PxOutputStream& toStream( PxOutputStream& ioStream, const char* inFormat, const TDataType inData )
{
char buffer[128] = { 0 };
Ps::snprintf( buffer, 128, inFormat, inData );
ioStream << buffer;
return ioStream;
}
struct endl_obj {};
//static endl_obj endl;
inline PxOutputStream& operator << ( PxOutputStream& ioStream, bool inData ) { ioStream << (inData ? "true" : "false"); return ioStream; }
inline PxOutputStream& operator << ( PxOutputStream& ioStream, PxI32 inData ) { return toStream( ioStream, "%d", inData ); }
inline PxOutputStream& operator << ( PxOutputStream& ioStream, PxU16 inData ) { return toStream( ioStream, "%u", PxU32(inData) ); }
inline PxOutputStream& operator << ( PxOutputStream& ioStream, PxU8 inData ) { return toStream( ioStream, "%u", PxU32(inData) ); }
inline PxOutputStream& operator << ( PxOutputStream& ioStream, char inData ) { return toStream( ioStream, "%c", inData ); }
inline PxOutputStream& operator << ( PxOutputStream& ioStream, PxU32 inData ) { return toStream( ioStream, "%u", inData ); }
inline PxOutputStream& operator << ( PxOutputStream& ioStream, PxU64 inData ) { return toStream( ioStream, "%" PX_PRIu64, inData ); }
inline PxOutputStream& operator << ( PxOutputStream& ioStream, const void* inData ) { return ioStream << static_cast<uint64_t>(reinterpret_cast<size_t>(inData)); }
inline PxOutputStream& operator << ( PxOutputStream& ioStream, PxF32 inData ) { return toStream( ioStream, "%g", PxF64(inData) ); }
inline PxOutputStream& operator << ( PxOutputStream& ioStream, PxF64 inData ) { return toStream( ioStream, "%g", inData ); }
inline PxOutputStream& operator << ( PxOutputStream& ioStream, endl_obj) { return ioStream << "\n"; }
inline PxOutputStream& operator << ( PxOutputStream& ioStream, const PxVec3& inData )
{
ioStream << inData[0];
ioStream << " ";
ioStream << inData[1];
ioStream << " ";
ioStream << inData[2];
return ioStream;
}
inline PxOutputStream& operator << ( PxOutputStream& ioStream, const PxQuat& inData )
{
ioStream << inData.x;
ioStream << " ";
ioStream << inData.y;
ioStream << " ";
ioStream << inData.z;
ioStream << " ";
ioStream << inData.w;
return ioStream;
}
inline PxOutputStream& operator << ( PxOutputStream& ioStream, const PxTransform& inData )
{
ioStream << inData.q;
ioStream << " ";
ioStream << inData.p;
return ioStream;
}
inline PxOutputStream& operator << ( PxOutputStream& ioStream, const PxBounds3& inData )
{
ioStream << inData.minimum;
ioStream << " ";
ioStream << inData.maximum;
return ioStream;
}
inline PxOutputStream& operator << ( PxOutputStream& ioStream, const PxFilterData& inData )
{
ioStream << inData.word0 << " " << inData.word1 << " " << inData.word2 << " " << inData.word3;
return ioStream;
}
inline PxOutputStream& operator << ( PxOutputStream& ioStream, struct PxMetaDataPlane& inData )
{
ioStream << inData.normal;
ioStream << " ";
ioStream << inData.distance;
return ioStream;
}
}
#endif

View File

@ -0,0 +1,245 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
DEFINE_REPX_DEFAULT_PROPERTY("PxBoxGeometry.HalfExtents", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphereGeometry.Radius", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxConvexMeshGeometry.Scale.Scale", "1 1 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxConvexMeshGeometry.Scale.Rotation", "0 0 0 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxConvexMeshGeometry.ConvexMesh", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTriangleMeshGeometry.Scale.Scale", "1 1 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTriangleMeshGeometry.Scale.Rotation", "0 0 0 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTriangleMeshGeometry.MeshFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTriangleMeshGeometry.TriangleMesh", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.HeightField", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.HeightScale", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.RowScale", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.ColumnScale", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.HeightFieldFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTolerancesScale.Length", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTolerancesScale.Mass", "1000" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTolerancesScale.Speed", "10" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.DynamicFriction", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.StaticFriction", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.DynamicFrictionV", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.StaticFrictionV", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.DirOfAnisotropy", "1 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.FrictionCombineMode", "eAVERAGE" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.RestitutionCombineMode", "eAVERAGE" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.UserData", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.LocalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.SimulationFilterData", "0 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.QueryFilterData", "0 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.ContactOffset", "0.02" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.RestOffset", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.Flags", "eSIMULATION_SHAPE|eSCENE_QUERY_SHAPE|eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.UserData", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.ActorFlags", "eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.DominanceGroup", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.OwnerClient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.ClientBehaviorBits", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.UserData", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.GlobalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.ActorFlags", "eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.DominanceGroup", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.OwnerClient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.ClientBehaviorBits", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.UserData", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.CMassLocalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.Mass", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.MassSpaceInertiaTensor", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.GlobalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.LinearVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.AngularVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.LinearDamping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.AngularDamping", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.MaxAngularVelocity", "7" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.SleepEnergyThreshold", "0.005" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.SolverIterationCounts.minPositionIters", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.SolverIterationCounts.minVelocityIters", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.ContactReportThreshold", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.RigidDynamicFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.ParentPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.ChildPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TargetOrientation", "0 0 0 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TargetVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.InternalCompliance", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.ExternalCompliance", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.SwingLimit.yLimit", "0.78539816339" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.SwingLimit.zLimit", "0.78539816339" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.SwingLimitEnabled", "false" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TwistLimit.lower", "-0.78539816339" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TwistLimit.upper", "0.78539816339" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TwistLimitEnabled", "false" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.ActorFlags", "eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.DominanceGroup", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.OwnerClient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.ClientBehaviorBits", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.UserData", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.CMassLocalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.Mass", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.MassSpaceInertiaTensor", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.GlobalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.LinearVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.AngularVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.MaxProjectionIterations", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.SeparationTolerance", "0.1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.InternalDriveIterations", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.ExternalDriveIterations", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.SolverIterationCounts.minPositionIters", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.SolverIterationCounts.minVelocityIters", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.UserData", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.UserData", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eX", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eY", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eZ", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eTWIST", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eSWING1", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eSWING2", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.Value", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Upper", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Lower", "-1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.YAngle", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.ZAngle", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eX.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eX.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eX.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eX.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eY.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eY.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eY.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eY.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eZ.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eZ.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eZ.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eZ.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSWING.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSWING.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSWING.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSWING.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eTWIST.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eTWIST.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eTWIST.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eTWIST.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSLERP.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSLERP.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSLERP.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSLERP.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.DrivePosition", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.DriveVelocity.linear", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.DriveVelocity.angular", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.ProjectionAngularTolerance", "3.14159" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.UserData", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.ProjectionAngularTolerance", "3.14159" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.UserData", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.MinDistance", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.MaxDistance", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Tolerance", "0.025" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.DistanceJointFlags", "eMAX_DISTANCE_ENABLED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.UserData", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Upper", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Lower", "-1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.DriveVelocity", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.DriveForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.DriveGearRatio", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.RevoluteJointFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.ProjectionAngularTolerance", "3.14159" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.UserData", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.ContactDistance", "0.01" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Upper", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Lower", "-3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.PrismaticJointFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.ProjectionAngularTolerance", "3.14159" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.UserData", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.YAngle", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.ZAngle", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.SphericalJointFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("THEEND", "false" )

View File

@ -0,0 +1,274 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
DEFINE_REPX_DEFAULT_PROPERTY("PxTolerancesScale.Length", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTolerancesScale.Mass", "1000" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTolerancesScale.Speed", "10" )
DEFINE_REPX_DEFAULT_PROPERTY("PxBoxGeometry.HalfExtents", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphereGeometry.Radius", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxConvexMeshGeometry.Scale.Scale", "1 1 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxConvexMeshGeometry.Scale.Rotation", "0 0 0 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxConvexMeshGeometry.ConvexMesh", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTriangleMeshGeometry.Scale.Scale", "1 1 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTriangleMeshGeometry.Scale.Rotation", "0 0 0 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTriangleMeshGeometry.MeshFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTriangleMeshGeometry.TriangleMesh", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.HeightField", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.HeightScale", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.RowScale", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.ColumnScale", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.HeightFieldFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.DynamicFriction", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.StaticFriction", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.DynamicFrictionV", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.StaticFrictionV", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.DirOfAnisotropy", "1 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.FrictionCombineMode", "eAVERAGE" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.RestitutionCombineMode", "eAVERAGE" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.LocalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.SimulationFilterData", "0 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.QueryFilterData", "0 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.ContactOffset", "0.02" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.RestOffset", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.Flags", "eSIMULATION_SHAPE|eSCENE_QUERY_SHAPE|eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.ActorFlags", "eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.DominanceGroup", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.OwnerClient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.ClientBehaviorBits", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.GlobalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.ActorFlags", "eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.DominanceGroup", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.OwnerClient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.ClientBehaviorBits", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.GlobalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.CMassLocalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.Mass", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.MassSpaceInertiaTensor", "1 1 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.LinearVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.AngularVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.LinearDamping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.AngularDamping", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.MaxAngularVelocity", "7" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.SleepThreshold", "0.005" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.SolverIterationCounts.minPositionIters", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.SolverIterationCounts.minVelocityIters", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.ContactReportThreshold", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.RigidDynamicFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.ParentPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.ChildPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TargetOrientation", "0 0 0 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TargetVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.InternalCompliance", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.ExternalCompliance", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.SwingLimit.yLimit", "0.78539816339" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.SwingLimit.zLimit", "0.78539816339" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TangentialSpring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TangentialDamping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.SwingLimitContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.SwingLimitEnabled", "false" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TwistLimit.lower", "-0.78539816339" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TwistLimit.upper", "0.78539816339" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TwistLimitEnabled", "false" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TwistLimitContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.ActorFlags", "eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.DominanceGroup", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.OwnerClient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.ClientBehaviorBits", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.GlobalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.CMassLocalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.Mass", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.MassSpaceInertiaTensor", "1 1 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.LinearVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.AngularVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.MaxProjectionIterations", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.SeparationTolerance", "0.1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.InternalDriveIterations", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.ExternalDriveIterations", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.SolverIterationCounts.minPositionIters", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.SolverIterationCounts.minVelocityIters", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.SleepThreshold", "0.005" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Actors.actor0", "8887040" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Actors.actor1", "8887456" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LocalPose.eACTOR0", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LocalPose.eACTOR1", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eX", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eY", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eZ", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eTWIST", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eSWING1", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eSWING2", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.Value", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Upper", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Lower", "-1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.YAngle", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.ZAngle", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eX.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eX.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eX.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eX.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eY.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eY.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eY.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eY.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eZ.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eZ.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eZ.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eZ.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSWING.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSWING.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSWING.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSWING.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eTWIST.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eTWIST.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eTWIST.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eTWIST.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSLERP.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSLERP.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSLERP.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSLERP.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.DrivePosition", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.DriveVelocity.linear", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.DriveVelocity.angular", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.ProjectionAngularTolerance", "3.14159" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.Actors.actor0", "8887040" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.Actors.actor1", "8887456" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.LocalPose.eACTOR0", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.LocalPose.eACTOR1", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.ProjectionAngularTolerance", "3.14159" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Actors.actor0", "8887040" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Actors.actor1", "8887456" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.LocalPose.eACTOR0", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.LocalPose.eACTOR1", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.MinDistance", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.MaxDistance", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Tolerance", "0.025" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.DistanceJointFlags", "eMAX_DISTANCE_ENABLED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Actors.actor0", "8887040" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Actors.actor1", "8887456" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.LocalPose.eACTOR0", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.LocalPose.eACTOR1", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Upper", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Lower", "-1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.DriveVelocity", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.DriveForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.DriveGearRatio", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.RevoluteJointFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.ProjectionAngularTolerance", "3.14159" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Actors.actor0", "8887040" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Actors.actor1", "8887456" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.LocalPose.eACTOR0", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.LocalPose.eACTOR1", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.ContactDistance", "0.01" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Upper", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Lower", "-3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.PrismaticJointFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.ProjectionAngularTolerance", "3.14159" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.Actors.actor0", "8887040" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.Actors.actor1", "8887456" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LocalPose.eACTOR0", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LocalPose.eACTOR1", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.YAngle", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.ZAngle", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.SphericalJointFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.ActorFlags", "eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.DominanceGroup", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.OwnerClient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.ClientBehaviorBits", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.MotionConstraintScaleBias.scale", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.MotionConstraintScaleBias.bias", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.GlobalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.ExternalAcceleration", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.DampingCoefficient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.SolverFrequency", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.SleepLinearVelocity", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("THEEND", "false" )

View File

@ -0,0 +1,313 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
DEFINE_REPX_DEFAULT_PROPERTY("PxTolerancesScale.Length", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTolerancesScale.Mass", "1000" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTolerancesScale.Speed", "10" )
DEFINE_REPX_DEFAULT_PROPERTY("PxBoxGeometry.HalfExtents", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphereGeometry.Radius", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxConvexMeshGeometry.Scale.Scale", "1 1 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxConvexMeshGeometry.Scale.Rotation", "0 0 0 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxConvexMeshGeometry.ConvexMesh", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTriangleMeshGeometry.Scale.Scale", "1 1 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTriangleMeshGeometry.Scale.Rotation", "0 0 0 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTriangleMeshGeometry.MeshFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxTriangleMeshGeometry.TriangleMesh", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.HeightField", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.HeightScale", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.RowScale", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.ColumnScale", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxHeightFieldGeometry.HeightFieldFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.DynamicFriction", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.StaticFriction", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.FrictionCombineMode", "eAVERAGE" )
DEFINE_REPX_DEFAULT_PROPERTY("PxMaterial.RestitutionCombineMode", "eAVERAGE" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.LocalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.SimulationFilterData", "0 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.QueryFilterData", "0 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.ContactOffset", "0.02" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.RestOffset", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.Flags", "eSIMULATION_SHAPE|eSCENE_QUERY_SHAPE|eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxShape.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.ActorFlags", "eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.DominanceGroup", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.OwnerClient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.ClientBehaviorBits", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidStatic.GlobalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.ActorFlags", "eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.DominanceGroup", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.OwnerClient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.ClientBehaviorBits", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.GlobalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.CMassLocalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.Mass", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.MassSpaceInertiaTensor", "1 1 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.LinearVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.AngularVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.LinearDamping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.AngularDamping", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.MaxAngularVelocity", "7" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.SleepThreshold", "0.005" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.SolverIterationCounts.minPositionIters", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.SolverIterationCounts.minVelocityIters", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.ContactReportThreshold", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRigidDynamic.RigidDynamicFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.ParentPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.ChildPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TargetOrientation", "0 0 0 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TargetVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.InternalCompliance", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.ExternalCompliance", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.SwingLimit.yLimit", "0.78539816339" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.SwingLimit.zLimit", "0.78539816339" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TangentialSpring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TangentialDamping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.SwingLimitContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.SwingLimitEnabled", "false" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TwistLimit.lower", "-0.78539816339" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TwistLimit.upper", "0.78539816339" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TwistLimitEnabled", "false" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationJoint.TwistLimitContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.ActorFlags", "eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.DominanceGroup", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.OwnerClient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.ClientBehaviorBits", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.GlobalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.CMassLocalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.Mass", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.MassSpaceInertiaTensor", "1 1 1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.LinearVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulationLink.AngularVelocity", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.MaxProjectionIterations", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.SeparationTolerance", "0.1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.InternalDriveIterations", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.ExternalDriveIterations", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.SolverIterationCounts.minPositionIters", "4" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.SolverIterationCounts.minVelocityIters", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.SleepThreshold", "0.005" )
DEFINE_REPX_DEFAULT_PROPERTY("PxArticulation.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Actors.actor0", "8887040" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Actors.actor1", "8887456" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LocalPose.eACTOR0", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LocalPose.eACTOR1", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eX", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eY", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eZ", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eTWIST", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eSWING1", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Motion.eSWING2", "eLOCKED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.LinearLimit.Value", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Upper", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.TwistLimit.Lower", "-1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.YAngle", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.SwingLimit.ZAngle", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eX.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eX.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eX.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eX.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eY.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eY.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eY.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eY.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eZ.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eZ.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eZ.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eZ.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSWING.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSWING.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSWING.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSWING.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eTWIST.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eTWIST.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eTWIST.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eTWIST.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSLERP.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSLERP.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSLERP.ForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.Drive.eSLERP.Flags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.DrivePosition", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.DriveVelocity.linear", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.DriveVelocity.angular", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("PxD6Joint.ProjectionAngularTolerance", "3.14159" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.Actors.actor0", "8887040" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.Actors.actor1", "8887456" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.LocalPose.eACTOR0", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.LocalPose.eACTOR1", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("PxFixedJoint.ProjectionAngularTolerance", "3.14159" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Actors.actor0", "8887040" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Actors.actor1", "8887456" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.LocalPose.eACTOR0", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.LocalPose.eACTOR1", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.MinDistance", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.MaxDistance", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Tolerance", "0.025" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxDistanceJoint.DistanceJointFlags", "eMAX_DISTANCE_ENABLED" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Actors.actor0", "8887040" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Actors.actor1", "8887456" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.LocalPose.eACTOR0", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.LocalPose.eACTOR1", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Upper", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.Limit.Lower", "-1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.DriveVelocity", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.DriveForceLimit", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.DriveGearRatio", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.RevoluteJointFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("PxRevoluteJoint.ProjectionAngularTolerance", "3.14159" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Actors.actor0", "8887040" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Actors.actor1", "8887456" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.LocalPose.eACTOR0", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.LocalPose.eACTOR1", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.ContactDistance", "0.01" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Upper", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.Limit.Lower", "-3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.PrismaticJointFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("PxPrismaticJoint.ProjectionAngularTolerance", "3.14159" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.Actors.actor0", "8887040" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.Actors.actor1", "8887456" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LocalPose.eACTOR0", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LocalPose.eACTOR1", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.BreakForce.force", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.BreakForce.torque", "3.40282e+038" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.ConstraintFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.Restitution", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.Spring", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.ContactDistance", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.YAngle", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.LimitCone.ZAngle", "1.5708" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.SphericalJointFlags", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxSphericalJoint.ProjectionLinearTolerance", "1e+010" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.Name", "" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.ActorFlags", "eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.DominanceGroup", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.OwnerClient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.ClientBehaviorBits", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.MotionConstraintScaleBias.scale", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.MotionConstraintScaleBias.bias", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.GlobalPose", "0 0 0 1 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.ExternalAcceleration", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.DampingCoefficient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.SolverFrequency", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.SleepLinearVelocity", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.InertiaScale", "1" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.FrictionCoefficient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.DragCoefficient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxCloth.CollisionMassScale", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.ActorFlags", "eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.DominanceGroup", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.OwnerClient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.ExternalAcceleration", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.ParticleMass", "0.001" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.Restitution", "0.5" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.DynamicFriction", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.StaticFriction", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.SimulationFilterData", "0 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.MaxMotionDistance", "0.06" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.RestOffset", "0.004" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.ContactOffset", "0.008" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.GridSize", "0.96" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.ProjectionPlane", "0 0 1 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.ParticleReadDataFlags", "ePOSITION_BUFFER|eFLAGS_BUFFER" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleSystem.ParticleBaseFlags", "eCOLLISION_WITH_DYNAMIC_ACTORS|eENABLED|ePER_PARTICLE_REST_OFFSET|ePER_PARTICLE_COLLISION_CACHE_HINT")
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.ActorFlags", "eVISUALIZATION" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.DominanceGroup", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.OwnerClient", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.Damping", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.ExternalAcceleration", "0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.ParticleMass", "0.001" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.Restitution", "0.5" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.DynamicFriction", "0.05" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.StaticFriction", "0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.SimulationFilterData", "0 0 0 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.MaxMotionDistance", "0.06" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.RestOffset", "0.004" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.ContactOffset", "0.008" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.GridSize", "0.64" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.ProjectionPlane", "0 0 1 0" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.Stiffness", "20" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.Viscosity", "6" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.RestParticleDistance", "0.02" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.ParticleReadDataFlags", "ePOSITION_BUFFER|eFLAGS_BUFFER" )
DEFINE_REPX_DEFAULT_PROPERTY("PxParticleFluid.ParticleBaseFlags", "eCOLLISION_WITH_DYNAMIC_ACTORS|eENABLED|ePER_PARTICLE_REST_OFFSET|ePER_PARTICLE_COLLISION_CACHE_HINT")
DEFINE_REPX_DEFAULT_PROPERTY("PxAggregate.SelfCollision", "false" )
DEFINE_REPX_DEFAULT_PROPERTY("THEEND", "false" )

View File

@ -0,0 +1,173 @@
//
// 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-2021 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_REPXCOLLECTION_H
#define PX_REPXCOLLECTION_H
#include "common/PxTolerancesScale.h"
#include "extensions/PxRepXSerializer.h"
namespace physx { namespace Sn {
struct XmlNode;
struct RepXCollectionItem
{
PxRepXObject liveObject;
XmlNode* descriptor;
RepXCollectionItem( PxRepXObject inItem = PxRepXObject(), XmlNode* inDescriptor = NULL )
: liveObject( inItem )
, descriptor( inDescriptor )
{
}
};
struct RepXDefaultEntry
{
const char* name;
const char* value;
RepXDefaultEntry( const char* pn, const char* val ) : name( pn ), value( val ){}
};
/**
* The result of adding an object to the collection.
*/
struct RepXAddToCollectionResult
{
enum Enum
{
Success,
SerializerNotFound,
InvalidParameters, //Null data passed in.
AlreadyInCollection
};
PxSerialObjectId collectionId;
Enum result;
RepXAddToCollectionResult( Enum inResult = Success, const PxSerialObjectId inId = 0 )
: collectionId( inId )
, result( inResult )
{
}
bool isValid() { return result == Success && collectionId != 0; }
};
/**
* A RepX collection contains a set of static data objects that can be transformed
* into live objects. It uses RepX serializer to do two transformations:
* live object <-> collection object (descriptor)
* collection object <-> file system.
*
* A live object is considered to be something live in the physics
* world such as a material or a rigidstatic.
*
* A collection object is a piece of data from which a live object
* of identical characteristics can be created.
*
* Clients need to pass PxCollection so that objects can resolve
* references. In addition, objects must be added in an order such that
* references can be resolved in the first place. So objects must be added
* to the collection *after* objects they are dependent upon.
*
* When deserializing from a file, the collection will allocate char*'s that will
* not be freed when the collection itself is freed. The user must be responsible
* for these character allocations.
*/
class RepXCollection
{
protected:
virtual ~RepXCollection(){}
public:
virtual void destroy() = 0;
/**
* Set the scale on this collection. The scale is saved with the collection.
*
* If the scale wasn't set, it will be invalid.
*/
virtual void setTolerancesScale( const PxTolerancesScale& inScale ) = 0;
/**
* Get the scale that was set at collection creation time or at load time.
* If this is a loaded file and the source data does not contain a scale
* this value will be invalid (PxTolerancesScale::isValid()).
*/
virtual PxTolerancesScale getTolerancesScale() const = 0;
/**
* Set the up vector on this collection. The up vector is saved with the collection.
*
* If the up vector wasn't set, it will be (0,0,0).
*/
virtual void setUpVector( const PxVec3& inUpVector ) = 0;
/**
* If the up vector wasn't set, it will be (0,0,0). Else this will be the up vector
* optionally set when the collection was created.
*/
virtual PxVec3 getUpVector() const = 0;
virtual const char* getVersion() = 0;
static const char* getLatestVersion();
//Necessary accessor functions for translation/upgrading.
virtual const RepXCollectionItem* begin() const = 0;
virtual const RepXCollectionItem* end() const = 0;
//Performs a deep copy of the repx node.
virtual XmlNode* copyRepXNode( const XmlNode* srcNode ) = 0;
virtual void addCollectionItem( RepXCollectionItem inItem ) = 0;
//Create a new repx node with this name. Its value is unset.
virtual XmlNode& createRepXNode( const char* name ) = 0;
virtual RepXCollection& createCollection( const char* inVersionStr ) = 0;
//Release this when finished.
virtual XmlReaderWriter& createNodeEditor() = 0;
virtual PxAllocatorCallback& getAllocator() = 0;
virtual bool instantiateCollection( PxRepXInstantiationArgs& inArgs, PxCollection& inPxCollection ) = 0;
virtual RepXAddToCollectionResult addRepXObjectToCollection( const PxRepXObject& inObject, PxCollection* inCollection, PxRepXInstantiationArgs& inArgs ) = 0;
/**
* Save this collection out to a file stream. Uses the RepX serialize to perform
* collection object->file conversions.
*
* /param[in] inStream Write-only stream to save collection out to.
*/
virtual void save( PxOutputStream& inStream ) = 0;
};
} }
#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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "PxPhysicsAPI.h"
#include "PxMetaDataObjects.h"
#include "CmIO.h"
#include "SnPxStreamOperators.h"
#include "PsUtilities.h"
#include "SnXmlImpl.h"
#include "SnXmlSerializer.h"
#include "SnXmlDeserializer.h"
#include "SnRepXCoreSerializer.h"
using namespace physx::Sn;
namespace physx {
typedef PxReadOnlyPropertyInfo<PxPropertyInfoName::PxArticulationLink_InboundJoint, PxArticulationLink, PxArticulationJointBase *> TIncomingJointPropType;
//*************************************************************
// Actual RepXSerializer implementations for PxMaterial
//*************************************************************
PxMaterial* PxMaterialRepXSerializer::allocateObject( PxRepXInstantiationArgs& inArgs )
{
return inArgs.physics.createMaterial(0, 0, 0);
}
PxRepXObject PxShapeRepXSerializer::fileToObject( XmlReader& inReader, XmlMemoryAllocator& inAllocator, PxRepXInstantiationArgs& inArgs, PxCollection* inCollection )
{
PxProfileAllocatorWrapper wrapper( inAllocator.getAllocator() );
TReaderNameStack names( wrapper );
PxProfileArray<PxU32> contexts( wrapper );
bool hadError = false;
RepXVisitorReader<PxShape> theVisitor( names, contexts, inArgs, inReader, NULL, inAllocator, *inCollection, hadError );
Ps::Array<PxMaterial*> materials;
PxGeometry* geometry = NULL;
parseShape( theVisitor, geometry, materials );
if(hadError)
return PxRepXObject();
PxShape *theShape = inArgs.physics.createShape( *geometry, materials.begin(), Ps::to16(materials.size()) );
switch(geometry->getType())
{
case PxGeometryType::eSPHERE :
static_cast<PxSphereGeometry*>(geometry)->~PxSphereGeometry();
break;
case PxGeometryType::ePLANE :
static_cast<PxPlaneGeometry*>(geometry)->~PxPlaneGeometry();
break;
case PxGeometryType::eCAPSULE :
static_cast<PxCapsuleGeometry*>(geometry)->~PxCapsuleGeometry();
break;
case PxGeometryType::eBOX :
static_cast<PxBoxGeometry*>(geometry)->~PxBoxGeometry();
break;
case PxGeometryType::eCONVEXMESH :
static_cast<PxConvexMeshGeometry*>(geometry)->~PxConvexMeshGeometry();
break;
case PxGeometryType::eTRIANGLEMESH :
static_cast<PxTriangleMeshGeometry*>(geometry)->~PxTriangleMeshGeometry();
break;
case PxGeometryType::eHEIGHTFIELD :
static_cast<PxHeightFieldGeometry*>(geometry)->~PxHeightFieldGeometry();
break;
case PxGeometryType::eGEOMETRY_COUNT:
case PxGeometryType::eINVALID:
PX_ASSERT(0);
}
inAllocator.getAllocator().deallocate(geometry);
bool ret = readAllProperties( inArgs, inReader, theShape, inAllocator, *inCollection );
return ret ? PxCreateRepXObject(theShape) : PxRepXObject();
}
//*************************************************************
// Actual RepXSerializer implementations for PxTriangleMesh
//*************************************************************
template<typename TTriIndexElem>
inline void writeTriangle( MemoryBuffer& inTempBuffer, const Triangle<TTriIndexElem>& inTriangle )
{
inTempBuffer << inTriangle.mIdx0
<< " " << inTriangle.mIdx1
<< " " << inTriangle.mIdx2;
}
PxU32 materialAccess( const PxTriangleMesh* inMesh, PxU32 inIndex ) { return inMesh->getTriangleMaterialIndex( inIndex ); }
template<typename TDataType>
void writeDatatype( MemoryBuffer& inTempBuffer, const TDataType& inType ) { inTempBuffer << inType; }
void PxBVH33TriangleMeshRepXSerializer::objectToFileImpl( const PxBVH33TriangleMesh* mesh, PxCollection* /*inCollection*/, XmlWriter& inWriter, MemoryBuffer& inTempBuffer, PxRepXInstantiationArgs& inArgs )
{
bool hasMatIndex = mesh->getTriangleMaterialIndex(0) != 0xffff;
PxU32 numVertices = mesh->getNbVertices();
const PxVec3* vertices = mesh->getVertices();
writeBuffer( inWriter, inTempBuffer, 2, vertices, numVertices, "Points", writePxVec3 );
bool isU16 = mesh->getTriangleMeshFlags() & PxTriangleMeshFlag::e16_BIT_INDICES ? true : false;
PxU32 triCount = mesh->getNbTriangles();
const void* indices = mesh->getTriangles();
if ( isU16 )
writeBuffer( inWriter, inTempBuffer, 2, reinterpret_cast<const Triangle<PxU16>* >( indices ), triCount, "Triangles", writeTriangle<PxU16> );
else
writeBuffer( inWriter, inTempBuffer, 2, reinterpret_cast<const Triangle<PxU32>* >( indices ), triCount, "Triangles", writeTriangle<PxU32> );
if ( hasMatIndex )
writeBuffer( inWriter, inTempBuffer, 6, mesh, materialAccess, triCount, "materialIndices", writeDatatype<PxU32> );
//Cooked stream
PxTriangleMeshDesc meshDesc;
meshDesc.points.count = numVertices;
meshDesc.points.data = vertices;
meshDesc.points.stride = sizeof(PxVec3);
meshDesc.triangles.count = triCount;
meshDesc.triangles.data = indices;
meshDesc.triangles.stride = isU16?3*sizeof(PxU16):3*sizeof(PxU32);
if(isU16)
{
meshDesc.triangles.stride = sizeof(PxU16)*3;
meshDesc.flags |= PxMeshFlag::e16_BIT_INDICES;
}
else
{
meshDesc.triangles.stride = sizeof(PxU32)*3;
}
if(hasMatIndex)
{
PxMaterialTableIndex* materialIndices = new PxMaterialTableIndex[triCount];
for(PxU32 i = 0; i < triCount; i++)
materialIndices[i] = mesh->getTriangleMaterialIndex(i);
meshDesc.materialIndices.data = materialIndices;
meshDesc.materialIndices.stride = sizeof(PxMaterialTableIndex);
}
if(inArgs.cooker != NULL)
{
TMemoryPoolManager theManager(mAllocator);
MemoryBuffer theTempBuf( &theManager );
theTempBuf.clear();
inArgs.cooker->cookTriangleMesh( meshDesc, theTempBuf );
writeBuffer( inWriter, inTempBuffer, 16, theTempBuf.mBuffer, theTempBuf.mWriteOffset, "CookedData", writeDatatype<PxU8> );
}
delete []meshDesc.materialIndices.data;
}
PxRepXObject PxBVH33TriangleMeshRepXSerializer::fileToObject( XmlReader& inReader, XmlMemoryAllocator& inAllocator, PxRepXInstantiationArgs& inArgs, PxCollection* /*inCollection*/ )
{
//We can't do a simple inverse; we *have* to cook data to get a mesh.
PxTriangleMeshDesc theDesc;
readStridedBufferProperty<PxVec3>( inReader, "points", theDesc.points, inAllocator);
readStridedBufferProperty<Triangle<PxU32> >( inReader, "triangles", theDesc.triangles, inAllocator);
PxU32 triCount;
readStridedBufferProperty<PxMaterialTableIndex>( inReader, "materialIndices", theDesc.materialIndices, triCount, inAllocator);
PxStridedData cookedData;
cookedData.stride = sizeof(PxU8);
PxU32 dataSize;
readStridedBufferProperty<PxU8>( inReader, "CookedData", cookedData, dataSize, inAllocator);
TMemoryPoolManager theManager(inAllocator.getAllocator());
MemoryBuffer theTempBuf( &theManager );
// PxTriangleMesh* theMesh = NULL;
PxBVH33TriangleMesh* theMesh = NULL;
if(dataSize != 0)
{
theTempBuf.write(cookedData.data, dataSize*sizeof(PxU8));
// theMesh = inArgs.physics.createTriangleMesh( theTempBuf );
theMesh = static_cast<PxBVH33TriangleMesh*>(inArgs.physics.createTriangleMesh( theTempBuf ));
}
if(theMesh == NULL)
{
PX_ASSERT(inArgs.cooker);
theTempBuf.clear();
{
PxCookingParams params = inArgs.cooker->getParams();
params.midphaseDesc = PxMeshMidPhase::eBVH33;
inArgs.cooker->setParams(params);
}
inArgs.cooker->cookTriangleMesh( theDesc, theTempBuf );
// theMesh = inArgs.physics.createTriangleMesh( theTempBuf );
theMesh = static_cast<PxBVH33TriangleMesh*>(inArgs.physics.createTriangleMesh( theTempBuf ));
}
return PxCreateRepXObject( theMesh );
}
void PxBVH34TriangleMeshRepXSerializer::objectToFileImpl( const PxBVH34TriangleMesh* mesh, PxCollection* /*inCollection*/, XmlWriter& inWriter, MemoryBuffer& inTempBuffer, PxRepXInstantiationArgs& inArgs )
{
bool hasMatIndex = mesh->getTriangleMaterialIndex(0) != 0xffff;
PxU32 numVertices = mesh->getNbVertices();
const PxVec3* vertices = mesh->getVertices();
writeBuffer( inWriter, inTempBuffer, 2, vertices, numVertices, "Points", writePxVec3 );
bool isU16 = mesh->getTriangleMeshFlags() & PxTriangleMeshFlag::e16_BIT_INDICES ? true : false;
PxU32 triCount = mesh->getNbTriangles();
const void* indices = mesh->getTriangles();
if ( isU16 )
writeBuffer( inWriter, inTempBuffer, 2, reinterpret_cast<const Triangle<PxU16>* >( indices ), triCount, "Triangles", writeTriangle<PxU16> );
else
writeBuffer( inWriter, inTempBuffer, 2, reinterpret_cast<const Triangle<PxU32>* >( indices ), triCount, "Triangles", writeTriangle<PxU32> );
if ( hasMatIndex )
writeBuffer( inWriter, inTempBuffer, 6, mesh, materialAccess, triCount, "materialIndices", writeDatatype<PxU32> );
//Cooked stream
PxTriangleMeshDesc meshDesc;
meshDesc.points.count = numVertices;
meshDesc.points.data = vertices;
meshDesc.points.stride = sizeof(PxVec3);
meshDesc.triangles.count = triCount;
meshDesc.triangles.data = indices;
meshDesc.triangles.stride = isU16?3*sizeof(PxU16):3*sizeof(PxU32);
if(isU16)
{
meshDesc.triangles.stride = sizeof(PxU16)*3;
meshDesc.flags |= PxMeshFlag::e16_BIT_INDICES;
}
else
{
meshDesc.triangles.stride = sizeof(PxU32)*3;
}
if(hasMatIndex)
{
PxMaterialTableIndex* materialIndices = new PxMaterialTableIndex[triCount];
for(PxU32 i = 0; i < triCount; i++)
materialIndices[i] = mesh->getTriangleMaterialIndex(i);
meshDesc.materialIndices.data = materialIndices;
meshDesc.materialIndices.stride = sizeof(PxMaterialTableIndex);
}
if(inArgs.cooker != NULL)
{
TMemoryPoolManager theManager(mAllocator);
MemoryBuffer theTempBuf( &theManager );
theTempBuf.clear();
inArgs.cooker->cookTriangleMesh( meshDesc, theTempBuf );
writeBuffer( inWriter, inTempBuffer, 16, theTempBuf.mBuffer, theTempBuf.mWriteOffset, "CookedData", writeDatatype<PxU8> );
}
delete []meshDesc.materialIndices.data;
}
PxRepXObject PxBVH34TriangleMeshRepXSerializer::fileToObject( XmlReader& inReader, XmlMemoryAllocator& inAllocator, PxRepXInstantiationArgs& inArgs, PxCollection* /*inCollection*/ )
{
//We can't do a simple inverse; we *have* to cook data to get a mesh.
PxTriangleMeshDesc theDesc;
readStridedBufferProperty<PxVec3>( inReader, "points", theDesc.points, inAllocator);
readStridedBufferProperty<Triangle<PxU32> >( inReader, "triangles", theDesc.triangles, inAllocator);
PxU32 triCount;
readStridedBufferProperty<PxMaterialTableIndex>( inReader, "materialIndices", theDesc.materialIndices, triCount, inAllocator);
PxStridedData cookedData;
cookedData.stride = sizeof(PxU8);
PxU32 dataSize;
readStridedBufferProperty<PxU8>( inReader, "CookedData", cookedData, dataSize, inAllocator);
TMemoryPoolManager theManager(inAllocator.getAllocator());
MemoryBuffer theTempBuf( &theManager );
// PxTriangleMesh* theMesh = NULL;
PxBVH34TriangleMesh* theMesh = NULL;
if(dataSize != 0)
{
theTempBuf.write(cookedData.data, dataSize*sizeof(PxU8));
// theMesh = inArgs.physics.createTriangleMesh( theTempBuf );
theMesh = static_cast<PxBVH34TriangleMesh*>(inArgs.physics.createTriangleMesh( theTempBuf ));
}
if(theMesh == NULL)
{
PX_ASSERT(inArgs.cooker);
theTempBuf.clear();
{
PxCookingParams params = inArgs.cooker->getParams();
params.midphaseDesc = PxMeshMidPhase::eBVH34;
inArgs.cooker->setParams(params);
}
inArgs.cooker->cookTriangleMesh( theDesc, theTempBuf );
// theMesh = inArgs.physics.createTriangleMesh( theTempBuf );
theMesh = static_cast<PxBVH34TriangleMesh*>(inArgs.physics.createTriangleMesh( theTempBuf ));
}
return PxCreateRepXObject(theMesh);
}
//*************************************************************
// Actual RepXSerializer implementations for PxHeightField
//*************************************************************
void PxHeightFieldRepXSerializer::objectToFileImpl( const PxHeightField* inHeightField, PxCollection* inCollection, XmlWriter& inWriter, MemoryBuffer& inTempBuffer, PxRepXInstantiationArgs& /*inArgs*/)
{
PxHeightFieldDesc theDesc;
theDesc.nbRows = inHeightField->getNbRows();
theDesc.nbColumns = inHeightField->getNbColumns();
theDesc.format = inHeightField->getFormat();
theDesc.samples.stride = inHeightField->getSampleStride();
theDesc.samples.data = NULL;
theDesc.convexEdgeThreshold = inHeightField->getConvexEdgeThreshold();
theDesc.flags = inHeightField->getFlags();
PxU32 theCellCount = inHeightField->getNbRows() * inHeightField->getNbColumns();
PxU32 theSampleStride = sizeof( PxHeightFieldSample );
PxU32 theSampleBufSize = theCellCount * theSampleStride;
PxHeightFieldSample* theSamples = reinterpret_cast< PxHeightFieldSample*> ( inTempBuffer.mManager->allocate( theSampleBufSize ) );
inHeightField->saveCells( theSamples, theSampleBufSize );
theDesc.samples.data = theSamples;
writeAllProperties( &theDesc, inWriter, inTempBuffer, *inCollection );
writeStridedBufferProperty<PxHeightFieldSample>( inWriter, inTempBuffer, "samples", theDesc.samples, theDesc.nbRows * theDesc.nbColumns, 6, writeHeightFieldSample);
inTempBuffer.mManager->deallocate( reinterpret_cast<PxU8*>(theSamples) );
}
PxRepXObject PxHeightFieldRepXSerializer::fileToObject( XmlReader& inReader, XmlMemoryAllocator& inAllocator, PxRepXInstantiationArgs& inArgs, PxCollection* inCollection )
{
PX_ASSERT(inArgs.cooker);
PxHeightFieldDesc theDesc;
readAllProperties( inArgs, inReader, &theDesc, inAllocator, *inCollection );
//Now read the data...
PxU32 count = 0; //ignored becaues numRows and numColumns tells the story
readStridedBufferProperty<PxHeightFieldSample>( inReader, "samples", theDesc.samples, count, inAllocator);
PxHeightField* retval = inArgs.cooker->createHeightField( theDesc, inArgs.physics.getPhysicsInsertionCallback() );
return PxCreateRepXObject(retval);
}
//*************************************************************
// Actual RepXSerializer implementations for PxConvexMesh
//*************************************************************
void PxConvexMeshRepXSerializer::objectToFileImpl( const PxConvexMesh* mesh, PxCollection* /*inCollection*/, XmlWriter& inWriter, MemoryBuffer& inTempBuffer, PxRepXInstantiationArgs& inArgs )
{
writeBuffer( inWriter, inTempBuffer, 2, mesh->getVertices(), mesh->getNbVertices(), "points", writePxVec3 );
if(inArgs.cooker != NULL)
{
//Cache cooked Data
PxConvexMeshDesc theDesc;
theDesc.points.data = mesh->getVertices();
theDesc.points.stride = sizeof(PxVec3);
theDesc.points.count = mesh->getNbVertices();
theDesc.flags = PxConvexFlag::eCOMPUTE_CONVEX;
TMemoryPoolManager theManager(mAllocator);
MemoryBuffer theTempBuf( &theManager );
inArgs.cooker->cookConvexMesh( theDesc, theTempBuf );
writeBuffer( inWriter, inTempBuffer, 16, theTempBuf.mBuffer, theTempBuf.mWriteOffset, "CookedData", writeDatatype<PxU8> );
}
}
//Conversion from scene object to descriptor.
PxRepXObject PxConvexMeshRepXSerializer::fileToObject( XmlReader& inReader, XmlMemoryAllocator& inAllocator, PxRepXInstantiationArgs& inArgs, PxCollection* /*inCollection*/)
{
PxConvexMeshDesc theDesc;
readStridedBufferProperty<PxVec3>( inReader, "points", theDesc.points, inAllocator);
theDesc.flags = PxConvexFlag::eCOMPUTE_CONVEX;
PxStridedData cookedData;
cookedData.stride = sizeof(PxU8);
PxU32 dataSize;
readStridedBufferProperty<PxU8>( inReader, "CookedData", cookedData, dataSize, inAllocator);
TMemoryPoolManager theManager(inAllocator.getAllocator());
MemoryBuffer theTempBuf( &theManager );
PxConvexMesh* theMesh = NULL;
if(dataSize != 0)
{
theTempBuf.write(cookedData.data, dataSize*sizeof(PxU8));
theMesh = inArgs.physics.createConvexMesh( theTempBuf );
}
if(theMesh == NULL)
{
PX_ASSERT(inArgs.cooker);
theTempBuf.clear();
inArgs.cooker->cookConvexMesh( theDesc, theTempBuf );
theMesh = inArgs.physics.createConvexMesh( theTempBuf );
}
return PxCreateRepXObject(theMesh);
}
//*************************************************************
// Actual RepXSerializer implementations for PxRigidStatic
//*************************************************************
PxRigidStatic* PxRigidStaticRepXSerializer::allocateObject( PxRepXInstantiationArgs& inArgs )
{
return inArgs.physics.createRigidStatic( PxTransform(PxIdentity) );
}
//*************************************************************
// Actual RepXSerializer implementations for PxRigidDynamic
//*************************************************************
PxRigidDynamic* PxRigidDynamicRepXSerializer::allocateObject( PxRepXInstantiationArgs& inArgs )
{
return inArgs.physics.createRigidDynamic( PxTransform(PxIdentity) );
}
//*************************************************************
// Actual RepXSerializer implementations for PxArticulation
//*************************************************************
void PxArticulationRepXSerializer::objectToFileImpl( const PxArticulation* inObj, PxCollection* inCollection, XmlWriter& inWriter, MemoryBuffer& inTempBuffer, PxRepXInstantiationArgs& /*inArgs*/)
{
TNameStack nameStack( inTempBuffer.mManager->mWrapper );
Sn::TArticulationLinkLinkMap linkMap( inTempBuffer.mManager->mWrapper );
RepXVisitorWriter<PxArticulation> writer( nameStack, inWriter, inObj, inTempBuffer, *inCollection, &linkMap );
RepXPropertyFilter<RepXVisitorWriter<PxArticulation> > theOp( writer );
visitAllProperties<PxArticulation>( theOp );
}
PxArticulation* PxArticulationRepXSerializer::allocateObject( PxRepXInstantiationArgs& inArgs ) { return inArgs.physics.createArticulation(); }
//*************************************************************
// Actual RepXSerializer implementations for PxArticulationReducedCoordinate
//*************************************************************
void PxArticulationReducedCoordinateRepXSerializer::objectToFileImpl(const PxArticulationReducedCoordinate* inObj, PxCollection* inCollection, XmlWriter& inWriter, MemoryBuffer& inTempBuffer, PxRepXInstantiationArgs& /*inArgs*/)
{
TNameStack nameStack(inTempBuffer.mManager->mWrapper);
Sn::TArticulationLinkLinkMap linkMap(inTempBuffer.mManager->mWrapper);
RepXVisitorWriter<PxArticulationReducedCoordinate> writer(nameStack, inWriter, inObj, inTempBuffer, *inCollection, &linkMap);
RepXPropertyFilter<RepXVisitorWriter<PxArticulationReducedCoordinate> > theOp(writer);
visitAllProperties<PxArticulationReducedCoordinate>(theOp);
}
PxArticulationReducedCoordinate* PxArticulationReducedCoordinateRepXSerializer::allocateObject(PxRepXInstantiationArgs& inArgs) { return inArgs.physics.createArticulationReducedCoordinate(); }
//*************************************************************
// Actual RepXSerializer implementations for PxAggregate
//*************************************************************
void PxAggregateRepXSerializer::objectToFileImpl( const PxAggregate* data, PxCollection* inCollection, XmlWriter& inWriter, MemoryBuffer& inTempBuffer, PxRepXInstantiationArgs& /*inArgs*/)
{
PxArticulationLink *link = NULL;
inWriter.addAndGotoChild( "Actors" );
for(PxU32 i = 0; i < data->getNbActors(); ++i)
{
PxActor* actor;
if(data->getActors(&actor, 1, i))
{
link = actor->is<PxArticulationLink>();
}
if(link && !link->getInboundJoint() )
{
writeProperty( inWriter, *inCollection, inTempBuffer, "PxArticulationRef", &link->getArticulation());
}
else if( !link )
{
PxSerialObjectId theId = 0;
theId = inCollection->getId( *actor );
if( theId == 0 )
theId = static_cast<uint64_t>(reinterpret_cast<size_t>(actor));
writeProperty( inWriter, *inCollection, inTempBuffer, "PxActorRef", theId );
}
}
inWriter.leaveChild( );
writeProperty( inWriter, *inCollection, inTempBuffer, "NumActors", data->getNbActors() );
writeProperty( inWriter, *inCollection, inTempBuffer, "MaxNbActors", data->getMaxNbActors() );
writeProperty( inWriter, *inCollection, inTempBuffer, "SelfCollision", data->getSelfCollision() );
writeAllProperties( data, inWriter, inTempBuffer, *inCollection );
}
PxRepXObject PxAggregateRepXSerializer::fileToObject( XmlReader& inReader, XmlMemoryAllocator& inAllocator, PxRepXInstantiationArgs& inArgs, PxCollection* inCollection )
{
PxU32 numActors;
readProperty( inReader, "NumActors", numActors );
PxU32 maxNbActors;
readProperty( inReader, "MaxNbActors", maxNbActors );
bool selfCollision;
bool ret = readProperty( inReader, "SelfCollision", selfCollision );
PxAggregate* theAggregate = inArgs.physics.createAggregate(maxNbActors, selfCollision);
ret &= readAllProperties( inArgs, inReader, theAggregate, inAllocator, *inCollection );
inReader.pushCurrentContext();
if ( inReader.gotoChild( "Actors" ) )
{
inReader.pushCurrentContext();
for( bool matSuccess = inReader.gotoFirstChild(); matSuccess;
matSuccess = inReader.gotoNextSibling() )
{
const char* actorType = inReader.getCurrentItemName();
if ( 0 == physx::shdfnd::stricmp( actorType, "PxActorRef" ) )
{
PxActor *actor = NULL;
ret &= readReference<PxActor>( inReader, *inCollection, actor );
if(actor)
{
PxScene *currScene = actor->getScene();
if(currScene)
{
currScene->removeActor(*actor);
}
theAggregate->addActor(*actor);
}
}
else if ( 0 == physx::shdfnd::stricmp( actorType, "PxArticulationRef" ) )
{
PxArticulation* articulation = NULL;
ret &= readReference<PxArticulation>( inReader, *inCollection, articulation );
if(articulation)
{
PxScene *currScene = articulation->getScene();
if(currScene)
{
currScene->removeArticulation(*articulation);
}
theAggregate->addArticulation(*articulation);
}
}
}
inReader.popCurrentContext();
inReader.leaveChild();
}
inReader.popCurrentContext();
return ret ? PxCreateRepXObject(theAggregate) : PxRepXObject();
}
}

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-2021 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 SN_REPX_CORE_SERIALIZER_H
#define SN_REPX_CORE_SERIALIZER_H
/** \addtogroup RepXSerializers
@{
*/
#include "foundation/PxSimpleTypes.h"
#include "SnRepXSerializerImpl.h"
#if !PX_DOXYGEN
namespace physx
{
#endif
class XmlReader;
class XmlMemoryAllocator;
class XmlWriter;
class MemoryBuffer;
struct PxMaterialRepXSerializer : RepXSerializerImpl<PxMaterial>
{
PxMaterialRepXSerializer( PxAllocatorCallback& inCallback ) : RepXSerializerImpl<PxMaterial>( inCallback ) {}
virtual PxMaterial* allocateObject( PxRepXInstantiationArgs& );
};
struct PxShapeRepXSerializer : public RepXSerializerImpl<PxShape>
{
PxShapeRepXSerializer( PxAllocatorCallback& inCallback ) : RepXSerializerImpl<PxShape>( inCallback ) {}
virtual PxRepXObject fileToObject( XmlReader&, XmlMemoryAllocator&, PxRepXInstantiationArgs&, PxCollection* );
virtual PxShape* allocateObject( PxRepXInstantiationArgs& ) { return NULL; }
};
struct PxBVH33TriangleMeshRepXSerializer : public RepXSerializerImpl<PxBVH33TriangleMesh>
{
PxBVH33TriangleMeshRepXSerializer( PxAllocatorCallback& inCallback ) : RepXSerializerImpl<PxBVH33TriangleMesh>( inCallback ) {}
virtual void objectToFileImpl( const PxBVH33TriangleMesh*, PxCollection*, XmlWriter&, MemoryBuffer&, PxRepXInstantiationArgs& );
virtual PxRepXObject fileToObject( XmlReader&, XmlMemoryAllocator&, PxRepXInstantiationArgs&, PxCollection* );
virtual PxBVH33TriangleMesh* allocateObject( PxRepXInstantiationArgs& ) { return NULL; }
};
struct PxBVH34TriangleMeshRepXSerializer : public RepXSerializerImpl<PxBVH34TriangleMesh>
{
PxBVH34TriangleMeshRepXSerializer( PxAllocatorCallback& inCallback ) : RepXSerializerImpl<PxBVH34TriangleMesh>( inCallback ) {}
virtual void objectToFileImpl( const PxBVH34TriangleMesh*, PxCollection*, XmlWriter&, MemoryBuffer&, PxRepXInstantiationArgs& );
virtual PxRepXObject fileToObject( XmlReader&, XmlMemoryAllocator&, PxRepXInstantiationArgs&, PxCollection* );
virtual PxBVH34TriangleMesh* allocateObject( PxRepXInstantiationArgs& ) { return NULL; }
};
struct PxHeightFieldRepXSerializer : public RepXSerializerImpl<PxHeightField>
{
PxHeightFieldRepXSerializer( PxAllocatorCallback& inCallback ) : RepXSerializerImpl<PxHeightField>( inCallback ) {}
virtual void objectToFileImpl( const PxHeightField*, PxCollection*, XmlWriter&, MemoryBuffer&, PxRepXInstantiationArgs& );
virtual PxRepXObject fileToObject( XmlReader&, XmlMemoryAllocator&, PxRepXInstantiationArgs&, PxCollection* );
virtual PxHeightField* allocateObject( PxRepXInstantiationArgs& ) { return NULL; }
};
struct PxConvexMeshRepXSerializer : public RepXSerializerImpl<PxConvexMesh>
{
PxConvexMeshRepXSerializer( PxAllocatorCallback& inCallback ) : RepXSerializerImpl<PxConvexMesh>( inCallback ) {}
virtual void objectToFileImpl( const PxConvexMesh*, PxCollection*, XmlWriter&, MemoryBuffer&, PxRepXInstantiationArgs& );
virtual PxRepXObject fileToObject( XmlReader&, XmlMemoryAllocator&, PxRepXInstantiationArgs&, PxCollection* );
virtual PxConvexMesh* allocateObject( PxRepXInstantiationArgs& ) { return NULL; }
};
struct PxRigidStaticRepXSerializer : public RepXSerializerImpl<PxRigidStatic>
{
PxRigidStaticRepXSerializer( PxAllocatorCallback& inCallback ) : RepXSerializerImpl<PxRigidStatic>( inCallback ) {}
virtual PxRigidStatic* allocateObject( PxRepXInstantiationArgs& );
};
struct PxRigidDynamicRepXSerializer : public RepXSerializerImpl<PxRigidDynamic>
{
PxRigidDynamicRepXSerializer( PxAllocatorCallback& inCallback ) : RepXSerializerImpl<PxRigidDynamic>( inCallback ) {}
virtual PxRigidDynamic* allocateObject( PxRepXInstantiationArgs& );
};
struct PxArticulationRepXSerializer : public RepXSerializerImpl<PxArticulation>
{
PxArticulationRepXSerializer( PxAllocatorCallback& inCallback ) : RepXSerializerImpl<PxArticulation>( inCallback ) {}
virtual void objectToFileImpl( const PxArticulation*, PxCollection*, XmlWriter&, MemoryBuffer&, PxRepXInstantiationArgs& );
virtual PxArticulation* allocateObject( PxRepXInstantiationArgs& );
};
struct PxArticulationReducedCoordinateRepXSerializer : public RepXSerializerImpl<PxArticulationReducedCoordinate>
{
PxArticulationReducedCoordinateRepXSerializer(PxAllocatorCallback& inCallback) : RepXSerializerImpl<PxArticulationReducedCoordinate>(inCallback) {}
virtual void objectToFileImpl(const PxArticulationReducedCoordinate*, PxCollection*, XmlWriter&, MemoryBuffer&, PxRepXInstantiationArgs&);
virtual PxArticulationReducedCoordinate* allocateObject(PxRepXInstantiationArgs&);
};
struct PxAggregateRepXSerializer : public RepXSerializerImpl<PxAggregate>
{
PxAggregateRepXSerializer( PxAllocatorCallback& inCallback ) : RepXSerializerImpl<PxAggregate>( inCallback ) {}
virtual void objectToFileImpl( const PxAggregate*, PxCollection*, XmlWriter& , MemoryBuffer&, PxRepXInstantiationArgs& );
virtual PxRepXObject fileToObject( XmlReader&, XmlMemoryAllocator&, PxRepXInstantiationArgs&, PxCollection* );
virtual PxAggregate* allocateObject( PxRepXInstantiationArgs& ) { return NULL; }
};
#if !PX_DOXYGEN
} // namespace physx
#endif
#endif
/** @} */

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-2021 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_REPX_SERIALIZER_IMPL_H
#define PX_REPX_SERIALIZER_IMPL_H
#include "PsUserAllocated.h"
#include "SnXmlVisitorWriter.h"
#include "SnXmlVisitorReader.h"
namespace physx {
using namespace Sn;
/**
* The repx serializer impl takes the raw, untyped repx extension interface
* and implements the simpler functions plus does the reinterpret-casts required
* for any object to implement the serializer safely.
*/
template<typename TLiveType>
struct RepXSerializerImpl : public PxRepXSerializer, shdfnd::UserAllocated
{
protected:
RepXSerializerImpl( const RepXSerializerImpl& inOther );
RepXSerializerImpl& operator=( const RepXSerializerImpl& inOther );
public:
PxAllocatorCallback& mAllocator;
RepXSerializerImpl( PxAllocatorCallback& inAllocator )
: mAllocator( inAllocator )
{
}
virtual const char* getTypeName() { return PxTypeInfo<TLiveType>::name(); }
virtual void objectToFile( const PxRepXObject& inLiveObject, PxCollection* inCollection, XmlWriter& inWriter, MemoryBuffer& inTempBuffer, PxRepXInstantiationArgs& inArgs )
{
const TLiveType* theObj = reinterpret_cast<const TLiveType*>( inLiveObject.serializable );
objectToFileImpl( theObj, inCollection, inWriter, inTempBuffer, inArgs );
}
virtual PxRepXObject fileToObject( XmlReader& inReader, XmlMemoryAllocator& inAllocator, PxRepXInstantiationArgs& inArgs, PxCollection* inCollection )
{
TLiveType* theObj( allocateObject( inArgs ) );
if ( theObj )
if(fileToObjectImpl( theObj, inReader, inAllocator, inArgs, inCollection ))
return PxCreateRepXObject(theObj);
return PxRepXObject();
}
virtual void objectToFileImpl( const TLiveType* inObj, PxCollection* inCollection, XmlWriter& inWriter, MemoryBuffer& inTempBuffer, PxRepXInstantiationArgs& /*inArgs*/)
{
writeAllProperties( inObj, inWriter, inTempBuffer, *inCollection );
}
virtual bool fileToObjectImpl( TLiveType* inObj, XmlReader& inReader, XmlMemoryAllocator& inAllocator, PxRepXInstantiationArgs& inArgs, PxCollection* inCollection )
{
return readAllProperties( inArgs, inReader, inObj, inAllocator, *inCollection );
}
virtual TLiveType* allocateObject( PxRepXInstantiationArgs& inArgs ) = 0;
};
}
#endif

View File

@ -0,0 +1,465 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "foundation/PxMemory.h"
#include "CmPhysXCommon.h"
#include "SnXmlImpl.h"
#include "SnXmlReader.h"
#include "SnXmlMemoryAllocator.h"
#include "PsFoundation.h"
#include "SnRepXCollection.h"
#include "SnRepXUpgrader.h"
using namespace physx::profile;
namespace physx { namespace Sn {
#define DEFINE_REPX_DEFAULT_PROPERTY( name, val ) RepXDefaultEntry( name, val ),
static RepXDefaultEntry gRepX1_0Defaults[] = {
#include "SnRepX1_0Defaults.h"
};
static PxU32 gNumRepX1_0Default = sizeof( gRepX1_0Defaults ) / sizeof ( *gRepX1_0Defaults );
static RepXDefaultEntry gRepX3_1Defaults[] = {
#include "SnRepX3_1Defaults.h"
};
static PxU32 gNumRepX3_1Defaults = sizeof( gRepX3_1Defaults ) / sizeof ( *gRepX3_1Defaults );
static RepXDefaultEntry gRepX3_2Defaults[] = {
#include "SnRepX3_2Defaults.h"
};
static PxU32 gNumRepX3_2Defaults = sizeof( gRepX3_2Defaults ) / sizeof ( *gRepX3_2Defaults );
inline const char* nextPeriod( const char* str )
{
for( ++str; str && *str && *str != '.'; ++str ); //empty loop intentional
return str;
}
inline bool safeStrEq(const char* lhs, const char* rhs)
{
if (lhs == rhs)
return true;
//If they aren't equal, and one of them is null,
//then they can't be equal.
//This is assuming that the null char* is not equal to
//the empty "" char*.
if (!lhs || !rhs)
return false;
return ::strcmp(lhs, rhs) == 0;
}
typedef PxProfileHashMap<const char*, PxU32> TNameOffsetMap;
void setMissingPropertiesToDefault( XmlNode* topNode, XmlReaderWriter& editor, const RepXDefaultEntry* defaults, PxU32 numDefaults, TNameOffsetMap& map )
{
for ( XmlNode* child = topNode->mFirstChild; child != NULL; child = child->mNextSibling )
setMissingPropertiesToDefault( child, editor, defaults, numDefaults, map );
const TNameOffsetMap::Entry* entry( map.find( topNode->mName ) );
if ( entry )
{
XmlReaderWriter& theReader( editor );
theReader.setNode( *topNode );
char nameBuffer[512] = {0};
size_t nameLen = strlen( topNode->mName );
//For each default property entry for this node type.
for ( const RepXDefaultEntry* item = defaults + entry->second; strncmp( item->name, topNode->mName, nameLen ) == 0; ++item )
{
bool childAdded = false;
const char* nameStart = item->name + nameLen;
++nameStart;
theReader.pushCurrentContext();
const char* str = nameStart;
while( *str )
{
const char *period = nextPeriod( str );
size_t len = size_t(PxMin( period - str, ptrdiff_t(1023) )); //can't be too careful these days.
PxMemCopy( nameBuffer, str, PxU32(len) );
nameBuffer[len] = 0;
if ( theReader.gotoChild( nameBuffer ) == false )
{
childAdded = true;
theReader.addOrGotoChild( nameBuffer );
}
if (*period )
str = period + 1;
else
str = period;
}
if ( childAdded )
theReader.setCurrentItemValue( item->value );
theReader.popCurrentContext();
}
}
}
static void setMissingPropertiesToDefault( RepXCollection& collection, XmlReaderWriter& editor, const RepXDefaultEntry* defaults, PxU32 numDefaults )
{
PxProfileAllocatorWrapper wrapper( collection.getAllocator() );
//Release all strings at once, instead of piece by piece
XmlMemoryAllocatorImpl alloc( collection.getAllocator() );
//build a hashtable of the initial default value strings.
TNameOffsetMap nameOffsets( wrapper );
for ( PxU32 idx = 0; idx < numDefaults; ++idx )
{
const RepXDefaultEntry& item( defaults[idx] );
size_t nameLen = 0;
const char* periodPtr = nextPeriod (item.name);
for ( ; periodPtr && *periodPtr; ++periodPtr ) if( *periodPtr == '.' ) break;
if ( periodPtr == NULL || *periodPtr != '.' ) continue;
nameLen = size_t(periodPtr - item.name);
char* newMem = reinterpret_cast<char*>(alloc.allocate( PxU32(nameLen + 1) ));
PxMemCopy( newMem, item.name, PxU32(nameLen) );
newMem[nameLen] = 0;
if ( nameOffsets.find( newMem ) )
alloc.deallocate( reinterpret_cast<PxU8*>(newMem) );
else
nameOffsets.insert( newMem, idx );
}
//Run through each collection item, and recursively find it and its children
//If an object's name is in the hash map, check and add any properties that don't exist.
//else return.
for ( const RepXCollectionItem* item = collection.begin(), *end = collection.end(); item != end; ++ item )
{
RepXCollectionItem theItem( *item );
setMissingPropertiesToDefault( theItem.descriptor, editor, defaults, numDefaults, nameOffsets );
}
}
struct RecursiveTraversal
{
RecursiveTraversal(XmlReaderWriter& editor): mEditor(editor) {}
void traverse()
{
mEditor.pushCurrentContext();
updateNode();
for(bool exists = mEditor.gotoFirstChild(); exists; exists = mEditor.gotoNextSibling())
traverse();
mEditor.popCurrentContext();
}
virtual void updateNode() = 0;
virtual ~RecursiveTraversal() {}
XmlReaderWriter& mEditor;
protected:
RecursiveTraversal& operator=(const RecursiveTraversal&){return *this;}
};
RepXCollection& RepXUpgrader::upgrade10CollectionTo3_1Collection(RepXCollection& src)
{
XmlReaderWriter& editor( src.createNodeEditor() );
setMissingPropertiesToDefault(src, editor, gRepX1_0Defaults, gNumRepX1_0Default );
RepXCollection* dest = &src.createCollection("3.1.1");
for ( const RepXCollectionItem* item = src.begin(), *end = src.end(); item != end; ++ item )
{
//either src or dest could do the copy operation, it doesn't matter who does it.
RepXCollectionItem newItem( item->liveObject, src.copyRepXNode( item->descriptor ) );
editor.setNode( *const_cast<XmlNode*>( newItem.descriptor ) );
//Some old files have this name in their system.
editor.renameProperty( "MassSpaceInertia", "MassSpaceInertiaTensor" );
editor.renameProperty( "SleepEnergyThreshold", "SleepThreshold" );
if ( strstr( newItem.liveObject.typeName, "Joint" ) || strstr( newItem.liveObject.typeName, "joint" ) )
{
//Joints changed format a bit. old joints looked like:
/*
<Actor0 >1627536</Actor0>
<Actor1 >1628368</Actor1>
<LocalPose0 >0 0 0 1 0.5 0.5 0.5</LocalPose0>
<LocalPose1 >0 0 0 1 0.3 0.3 0.3</LocalPose1>*/
//New joints look like:
/*
<Actors >
<actor0 >58320336</actor0>
<actor1 >56353568</actor1>
</Actors>
<LocalPose >
<eACTOR0 >0 0 0 1 0.5 0.5 0.5</eACTOR0>
<eACTOR1 >0 0 0 1 0.3 0.3 0.3</eACTOR1>
</LocalPose>
*/
const char* actor0, *actor1, *lp0, *lp1;
editor.readAndRemoveProperty( "Actor0", actor0 );
editor.readAndRemoveProperty( "Actor1", actor1 );
editor.readAndRemoveProperty( "LocalPose0", lp0 );
editor.readAndRemoveProperty( "LocalPose1", lp1 );
editor.addOrGotoChild( "Actors" );
editor.writePropertyIfNotEmpty( "actor0", actor0 );
editor.writePropertyIfNotEmpty( "actor1", actor1 );
editor.leaveChild();
editor.addOrGotoChild( "LocalPose" );
editor.writePropertyIfNotEmpty( "eACTOR0", lp0 );
editor.writePropertyIfNotEmpty( "eACTOR1", lp1 );
editor.leaveChild();
}
//now desc owns the new node. Collections share a single allocation pool, however,
//which will get destroyed when all the collections referencing it are destroyed themselves.
//Data on nodes is shared between nodes, but the node structure itself is allocated.
dest->addCollectionItem( newItem );
}
editor.release();
src.destroy();
return *dest;
}
RepXCollection& RepXUpgrader::upgrade3_1CollectionTo3_2Collection(RepXCollection& src)
{
XmlReaderWriter& editor( src.createNodeEditor() );
setMissingPropertiesToDefault(src, editor, gRepX3_1Defaults, gNumRepX3_1Defaults );
RepXCollection* dest = &src.createCollection("3.2.0");
for ( const RepXCollectionItem* item = src.begin(), *end = src.end(); item != end; ++ item )
{
//either src or dest could do the copy operation, it doesn't matter who does it.
RepXCollectionItem newItem( item->liveObject, src.copyRepXNode( item->descriptor ) );
editor.setNode( *const_cast<XmlNode*>( newItem.descriptor ) );
if ( strstr( newItem.liveObject.typeName, "PxMaterial" ) )
{
editor.removeChild( "DynamicFrictionV" );
editor.removeChild( "StaticFrictionV" );
editor.removeChild( "dirOfAnisotropy" );
}
//now desc owns the new node. Collections share a single allocation pool, however,
//which will get destroyed when all the collections referencing it are destroyed themselves.
//Data on nodes is shared between nodes, but the node structure itself is allocated.
dest->addCollectionItem( newItem );
}
editor.release();
src.destroy();
return *dest;
}
RepXCollection& RepXUpgrader::upgrade3_2CollectionTo3_3Collection(RepXCollection& src)
{
XmlReaderWriter& editor( src.createNodeEditor() );
setMissingPropertiesToDefault(src, editor, gRepX3_2Defaults, gNumRepX3_2Defaults );
RepXCollection* dest = &src.createCollection("3.3.0");
struct RenameSpringToStiffness : public RecursiveTraversal
{
RenameSpringToStiffness(XmlReaderWriter& editor_): RecursiveTraversal(editor_) {}
void updateNode()
{
mEditor.renameProperty("Spring", "Stiffness");
mEditor.renameProperty("TangentialSpring", "TangentialStiffness");
}
};
struct UpdateArticulationSwingLimit : public RecursiveTraversal
{
UpdateArticulationSwingLimit(XmlReaderWriter& editor_): RecursiveTraversal(editor_) {}
void updateNode()
{
if(!Ps::stricmp(mEditor.getCurrentItemName(), "yLimit") && !Ps::stricmp(mEditor.getCurrentItemValue(), "0"))
mEditor.setCurrentItemValue("0.785398");
if(!Ps::stricmp(mEditor.getCurrentItemName(), "zLimit") && !Ps::stricmp(mEditor.getCurrentItemValue(), "0"))
mEditor.setCurrentItemValue("0.785398");
if(!Ps::stricmp(mEditor.getCurrentItemName(), "TwistLimit"))
{
mEditor.gotoFirstChild();
PxReal lower = PxReal(strtod(mEditor.getCurrentItemValue(), NULL));
mEditor.gotoNextSibling();
PxReal upper = PxReal(strtod(mEditor.getCurrentItemValue(), NULL));
mEditor.leaveChild();
if(lower>=upper)
{
mEditor.writePropertyIfNotEmpty("lower", "-0.785398");
mEditor.writePropertyIfNotEmpty("upper", "0.785398");
}
}
}
};
for ( const RepXCollectionItem* item = src.begin(), *end = src.end(); item != end; ++ item )
{
//either src or dest could do the copy operation, it doesn't matter who does it.
RepXCollectionItem newItem( item->liveObject, src.copyRepXNode( item->descriptor ) );
if ( strstr( newItem.liveObject.typeName, "PxCloth" ) || strstr( newItem.liveObject.typeName, "PxClothFabric" ) )
{
physx::shdfnd::getFoundation().error(PxErrorCode::eDEBUG_WARNING, __FILE__, __LINE__, "Didn't suppot PxCloth upgrate from 3.2 to 3.3! ");
continue;
}
if ( strstr( newItem.liveObject.typeName, "PxParticleSystem" ) || strstr( newItem.liveObject.typeName, "PxParticleFluid" ) )
{
editor.setNode( *const_cast<XmlNode*>( newItem.descriptor ) );
editor.renameProperty( "PositionBuffer", "Positions" );
editor.renameProperty( "VelocityBuffer", "Velocities" );
editor.renameProperty( "RestOffsetBuffer", "RestOffsets" );
}
if(strstr(newItem.liveObject.typeName, "PxPrismaticJoint" )
|| strstr(newItem.liveObject.typeName, "PxRevoluteJoint")
|| strstr(newItem.liveObject.typeName, "PxSphericalJoint")
|| strstr(newItem.liveObject.typeName, "PxD6Joint")
|| strstr(newItem.liveObject.typeName, "PxArticulation"))
{
editor.setNode( *const_cast<XmlNode*>( newItem.descriptor ) );
RenameSpringToStiffness(editor).traverse();
}
if(strstr(newItem.liveObject.typeName, "PxArticulation"))
{
editor.setNode( *const_cast<XmlNode*>( newItem.descriptor ) );
UpdateArticulationSwingLimit(editor).traverse();
}
//now dest owns the new node. Collections share a single allocation pool, however,
//which will get destroyed when all the collections referencing it are destroyed themselves.
//Data on nodes is shared between nodes, but the node structure itself is allocated.
dest->addCollectionItem( newItem );
}
editor.release();
src.destroy();
return *dest;
}
RepXCollection& RepXUpgrader::upgrade3_3CollectionTo3_4Collection(RepXCollection& src)
{
RepXCollection* dest = &src.createCollection("3.4.0");
for ( const RepXCollectionItem* item = src.begin(), *end = src.end(); item != end; ++ item )
{
if(strstr(item->liveObject.typeName, "PxTriangleMesh"))
{
PxRepXObject newMeshRepXObj("PxBVH33TriangleMesh", item->liveObject.serializable, item->liveObject.id);
XmlNode* newMeshNode = src.copyRepXNode( item->descriptor );
newMeshNode->mName = "PxBVH33TriangleMesh";
RepXCollectionItem newMeshItem(newMeshRepXObj, newMeshNode);
dest->addCollectionItem( newMeshItem );
continue;
}
RepXCollectionItem newItem( item->liveObject, src.copyRepXNode( item->descriptor ) );
dest->addCollectionItem( newItem );
}
src.destroy();
return *dest;
}
RepXCollection& RepXUpgrader::upgrade3_4CollectionTo4_0Collection(RepXCollection& src)
{
RepXCollection* dest = &src.createCollection("4.0.0");
for (const RepXCollectionItem* item = src.begin(), *end = src.end(); item != end; ++item)
{
if (strstr(item->liveObject.typeName, "PxParticleFluid") ||
strstr(item->liveObject.typeName, "PxParticleSystem") ||
strstr(item->liveObject.typeName, "PxClothFabric") ||
strstr(item->liveObject.typeName, "PxCloth"))
{
continue;
}
RepXCollectionItem newItem(item->liveObject, src.copyRepXNode(item->descriptor));
dest->addCollectionItem(newItem);
}
src.destroy();
return *dest;
}
RepXCollection& RepXUpgrader::upgradeCollection(RepXCollection& src)
{
const char* srcVersion = src.getVersion();
if( safeStrEq( srcVersion, RepXCollection::getLatestVersion() ))
return src;
typedef RepXCollection& (*UPGRADE_FUNCTION)(RepXCollection& src);
struct Upgrade { const char* versionString; UPGRADE_FUNCTION upgradeFunction; };
static const Upgrade upgradeTable[] =
{
{ "1.0", upgrade10CollectionTo3_1Collection },
{ "3.1", NULL },
{ "3.1.1", upgrade3_1CollectionTo3_2Collection },
{ "3.2.0", upgrade3_2CollectionTo3_3Collection },
{ "3.3.0", NULL },
{ "3.3.1", NULL },
{ "3.3.2", NULL },
{ "3.3.3", NULL },
{ "3.3.4", upgrade3_3CollectionTo3_4Collection },
{ "3.4.0", NULL },
{ "3.4.1", NULL },
{ "3.4.2", upgrade3_4CollectionTo4_0Collection }
}; //increasing order and complete
const PxU32 upgradeTableSize = sizeof(upgradeTable)/sizeof(upgradeTable[0]);
PxU32 repxVersion = UINT16_MAX;
for (PxU32 i=0; i<upgradeTableSize; i++)
{
if( safeStrEq( srcVersion, upgradeTable[i].versionString ))
{
repxVersion = i;
break;
}
}
RepXCollection* dest = &src;
for( PxU32 j = repxVersion; j < upgradeTableSize; j++ )
{
if( upgradeTable[j].upgradeFunction )
dest = &(upgradeTable[j].upgradeFunction)(*dest);
}
return *dest;
}
} }

View File

@ -0,0 +1,54 @@
//
// 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-2021 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_REPX_UPGRADER_H
#define PX_REPX_UPGRADER_H
#include "foundation/PxSimpleTypes.h"
namespace physx { namespace Sn {
class RepXCollection;
class RepXUpgrader
{
public:
//If a new collection is created, the source collection is destroyed.
//Thus you only need to release the new collection.
//This holds for all of the upgrade functions.
//So be aware, that the argument to these functions may not be valid
//after they are called, but the return value always will be valid.
static RepXCollection& upgradeCollection( RepXCollection& src );
static RepXCollection& upgrade10CollectionTo3_1Collection( RepXCollection& src );
static RepXCollection& upgrade3_1CollectionTo3_2Collection( RepXCollection& src );
static RepXCollection& upgrade3_2CollectionTo3_3Collection( RepXCollection& src );
static RepXCollection& upgrade3_3CollectionTo3_4Collection( RepXCollection& src );
static RepXCollection& upgrade3_4CollectionTo4_0Collection( RepXCollection& src );
};
} }
#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-2021 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_SIMPLEXMLWRITER_H
#define PX_SIMPLEXMLWRITER_H
#include "PsArray.h"
#include "SnXmlMemoryPoolStreams.h"
#include "CmPhysXCommon.h"
namespace physx { namespace Sn {
class SimpleXmlWriter
{
public:
struct STagWatcher
{
typedef SimpleXmlWriter TXmlWriterType;
TXmlWriterType& mWriter;
STagWatcher( const STagWatcher& inOther );
STagWatcher& operator-( const STagWatcher& inOther );
STagWatcher( TXmlWriterType& inWriter, const char* inTagName )
: mWriter( inWriter )
{
mWriter.beginTag( inTagName );
}
~STagWatcher() { mWriter.endTag(); }
protected:
STagWatcher& operator=(const STagWatcher&);
};
virtual ~SimpleXmlWriter(){}
virtual void beginTag( const char* inTagname ) = 0;
virtual void endTag() = 0;
virtual void addAttribute( const char* inName, const char* inValue ) = 0;
virtual void writeContentTag( const char* inTag, const char* inContent ) = 0;
virtual void addContent( const char* inContent ) = 0;
virtual PxU32 tabCount() = 0;
private:
SimpleXmlWriter& operator=(const SimpleXmlWriter&);
};
template<typename TStreamType>
class SimpleXmlWriterImpl : public SimpleXmlWriter
{
PxProfileAllocatorWrapper mWrapper;
TStreamType& mStream;
SimpleXmlWriterImpl( const SimpleXmlWriterImpl& inOther );
SimpleXmlWriterImpl& operator=( const SimpleXmlWriterImpl& inOther );
PxProfileArray<const char*> mTags;
bool mTagOpen;
PxU32 mInitialTagDepth;
public:
SimpleXmlWriterImpl( TStreamType& inStream, PxAllocatorCallback& inAllocator, PxU32 inInitialTagDepth = 0 )
: mWrapper( inAllocator )
, mStream( inStream )
, mTags( mWrapper )
, mTagOpen( false )
, mInitialTagDepth( inInitialTagDepth )
{
}
virtual ~SimpleXmlWriterImpl()
{
while( mTags.size() )
endTag();
}
PxU32 tabCount() { return mTags.size() + mInitialTagDepth; }
void writeTabs( PxU32 inSize )
{
inSize += mInitialTagDepth;
for ( PxU32 idx =0; idx < inSize; ++idx )
mStream << "\t";
}
void beginTag( const char* inTagname )
{
closeTag();
writeTabs(mTags.size());
mTags.pushBack( inTagname );
mStream << "<" << inTagname;
mTagOpen = true;
}
void addAttribute( const char* inName, const char* inValue )
{
PX_ASSERT( mTagOpen );
mStream << " " << inName << "=" << "\"" << inValue << "\"";
}
void closeTag(bool useNewline = true)
{
if ( mTagOpen )
{
mStream << " " << ">";
if (useNewline )
mStream << "\n";
}
mTagOpen = false;
}
void doEndOpenTag()
{
mStream << "</" << mTags.back() << ">" << "\n";
}
void endTag()
{
PX_ASSERT( mTags.size() );
if ( mTagOpen )
mStream << " " << "/>" << "\n";
else
{
writeTabs(mTags.size()-1);
doEndOpenTag();
}
mTagOpen = false;
mTags.popBack();
}
static bool IsNormalizableWhitespace(char c) { return c == 0x9 || c == 0xA || c == 0xD; }
static bool IsValidXmlCharacter(char c) { return IsNormalizableWhitespace(c) || c >= 0x20; }
void addContent( const char* inContent )
{
closeTag(false);
//escape xml
for( ; *inContent; inContent++ )
{
switch (*inContent)
{
case '<':
mStream << "&lt;";
break;
case '>':
mStream << "&gt;";
break;
case '&':
mStream << "&amp;";
break;
case '\'':
mStream << "&apos;";
break;
case '"':
mStream << "&quot;";
break;
default:
if (IsValidXmlCharacter(*inContent)) {
if (IsNormalizableWhitespace(*inContent))
{
char s[32];
Ps::snprintf(s, 32, "&#x%02X;", unsigned(*inContent));
mStream << s;
}
else
mStream << *inContent;
}
break;
}
}
}
void writeContentTag( const char* inTag, const char* inContent )
{
beginTag( inTag );
addContent( inContent );
doEndOpenTag();
mTags.popBack();
}
void insertXml( const char* inXml )
{
closeTag();
mStream << inXml;
}
};
struct BeginTag
{
const char* mTagName;
BeginTag( const char* inTagName )
: mTagName( inTagName ) { }
};
struct EndTag
{
EndTag() {}
};
struct Att
{
const char* mAttName;
const char* mAttValue;
Att( const char* inAttName, const char* inAttValue )
: mAttName( inAttName )
, mAttValue( inAttValue ) { }
};
struct Content
{
const char* mContent;
Content( const char* inContent )
: mContent( inContent ) { }
};
struct ContentTag
{
const char* mTagName;
const char* mContent;
ContentTag( const char* inTagName, const char* inContent )
: mTagName( inTagName )
, mContent( inContent ) { }
};
inline SimpleXmlWriter& operator<<( SimpleXmlWriter& inWriter, const BeginTag& inTag ) { inWriter.beginTag( inTag.mTagName ); return inWriter; }
inline SimpleXmlWriter& operator<<( SimpleXmlWriter& inWriter, const EndTag& inTag ) { PX_UNUSED(inTag); inWriter.endTag(); return inWriter; }
inline SimpleXmlWriter& operator<<( SimpleXmlWriter& inWriter, const Att& inTag ) { inWriter.addAttribute(inTag.mAttName, inTag.mAttValue); return inWriter; }
inline SimpleXmlWriter& operator<<( SimpleXmlWriter& inWriter, const Content& inTag ) { inWriter.addContent(inTag.mContent); return inWriter; }
inline SimpleXmlWriter& operator<<( SimpleXmlWriter& inWriter, const ContentTag& inTag ) { inWriter.writeContentTag(inTag.mTagName, inTag.mContent); return inWriter; }
inline void writeProperty( SimpleXmlWriter& inWriter, MemoryBuffer& tempBuffer, const char* inPropName )
{
PxU8 data = 0;
tempBuffer.write( &data, sizeof(PxU8) );
inWriter.writeContentTag( inPropName, reinterpret_cast<const char*>( tempBuffer.mBuffer ) );
tempBuffer.clear();
}
template<typename TDataType>
inline void writeProperty( SimpleXmlWriter& inWriter, MemoryBuffer& tempBuffer, const char* inPropName, TDataType inValue )
{
tempBuffer << inValue;
writeProperty( inWriter, tempBuffer, inPropName );
}
} }
#endif

View File

@ -0,0 +1,197 @@
//
// 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-2021 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_XML_DESERIALIZER_H
#define PX_XML_DESERIALIZER_H
#include "SnXmlVisitorReader.h"
namespace physx { namespace Sn {
//Definitions needed internally in the Serializer headers.
template<typename TTriIndexElem>
struct Triangle
{
TTriIndexElem mIdx0;
TTriIndexElem mIdx1;
TTriIndexElem mIdx2;
Triangle( TTriIndexElem inIdx0 = 0, TTriIndexElem inIdx1 = 0, TTriIndexElem inIdx2 = 0)
: mIdx0( inIdx0 )
, mIdx1( inIdx1 )
, mIdx2( inIdx2 )
{
}
};
struct XmlMemoryAllocateMemoryPoolAllocator
{
XmlMemoryAllocator* mAllocator;
XmlMemoryAllocateMemoryPoolAllocator( XmlMemoryAllocator* inAlloc ) : mAllocator( inAlloc ) {}
PxU8* allocate( PxU32 inSize ) { return mAllocator->allocate( inSize ); }
void deallocate( PxU8* inMem ) { mAllocator->deallocate( inMem ); }
};
inline bool isEmpty(const char *s)
{
while (*s != '\0')
{
if (!isspace(*s))
return false;
s++;
}
return true;
}
inline void strtoLong( Triangle<PxU32>& ioDatatype,const char*& ioData )
{
strto( ioDatatype.mIdx0, ioData );
strto( ioDatatype.mIdx1, ioData );
strto( ioDatatype.mIdx2, ioData );
}
inline void strtoLong( PxHeightFieldSample& ioDatatype,const char*& ioData )
{
PxU32 tempData;
strto( tempData, ioData );
if ( isBigEndian() )
{
PxU32& theItem(tempData);
PxU32 theDest = 0;
PxU8* theReadPtr( reinterpret_cast< PxU8* >( &theItem ) );
PxU8* theWritePtr( reinterpret_cast< PxU8* >( &theDest ) );
//A height field sample is a 16 bit number
//followed by two bytes.
//We write this out as a 32 bit integer, LE.
//Thus, on a big endian, we need to move the bytes
//around a bit.
//LE - 1 2 3 4
//BE - 4 3 2 1 - after convert from xml number
//Correct BE - 2 1 3 4, just like LE but with the 16 number swapped
theWritePtr[0] = theReadPtr[2];
theWritePtr[1] = theReadPtr[3];
theWritePtr[2] = theReadPtr[1];
theWritePtr[3] = theReadPtr[0];
theItem = theDest;
}
ioDatatype = *reinterpret_cast<PxHeightFieldSample*>( &tempData );
}
template<typename TDataType>
inline void readStridedFlagsProperty( XmlReader& ioReader, const char* inPropName, TDataType*& outData, PxU32& outStride, PxU32& outCount, XmlMemoryAllocator& inAllocator,
const PxU32ToName* inConversions)
{
const char* theSrcData;
outStride = sizeof( TDataType );
outData = NULL;
outCount = 0;
if ( ioReader.read( inPropName, theSrcData ) )
{
XmlMemoryAllocateMemoryPoolAllocator tempAllocator( &inAllocator );
MemoryBufferBase<XmlMemoryAllocateMemoryPoolAllocator> tempBuffer( &tempAllocator );
if ( theSrcData )
{
static PxU32 theCount = 0;
++theCount;
char* theStartData = const_cast< char*>( copyStr( &tempAllocator, theSrcData ) );
char* aData = strtok(theStartData, " \n");
while( aData )
{
TDataType tempValue;
stringToFlagsType( aData, inAllocator, tempValue, inConversions );
aData = strtok(NULL," \n");
tempBuffer.write( &tempValue, sizeof(TDataType) );
}
outData = reinterpret_cast< TDataType* >( tempBuffer.mBuffer );
outCount = tempBuffer.mWriteOffset / sizeof( TDataType );
tempAllocator.deallocate( reinterpret_cast<PxU8*>(theStartData) );
}
tempBuffer.releaseBuffer();
}
}
template<typename TDataType>
inline void readStridedBufferProperty( XmlReader& ioReader, const char* inPropName, TDataType*& outData, PxU32& outStride, PxU32& outCount, XmlMemoryAllocator& inAllocator)
{
const char* theSrcData;
outStride = sizeof( TDataType );
outData = NULL;
outCount = 0;
if ( ioReader.read( inPropName, theSrcData ) )
{
XmlMemoryAllocateMemoryPoolAllocator tempAllocator( &inAllocator );
MemoryBufferBase<XmlMemoryAllocateMemoryPoolAllocator> tempBuffer( &tempAllocator );
if ( theSrcData )
{
static PxU32 theCount = 0;
++theCount;
char* theStartData = const_cast< char*>( copyStr( &tempAllocator, theSrcData ) );
const char* theData = theStartData;
while( !isEmpty(theData) )
{
//These buffers are whitespace delimited.
TDataType theType;
strtoLong( theType, theData );
tempBuffer.write( &theType, sizeof(theType) );
}
outData = reinterpret_cast< TDataType* >( tempBuffer.mBuffer );
outCount = tempBuffer.mWriteOffset / sizeof( TDataType );
tempAllocator.deallocate( reinterpret_cast<PxU8*>(theStartData) );
}
tempBuffer.releaseBuffer();
}
}
template<typename TDataType>
inline void readStridedBufferProperty( XmlReader& ioReader, const char* inPropName, PxStridedData& ioData, PxU32& outCount, XmlMemoryAllocator& inAllocator)
{
TDataType* tempData = NULL;
readStridedBufferProperty<TDataType>( ioReader, inPropName, tempData, ioData.stride, outCount, inAllocator );
ioData.data = tempData;
}
template<typename TDataType>
inline void readStridedBufferProperty( XmlReader& ioReader, const char* inPropName, PxTypedStridedData<TDataType>& ioData, PxU32& outCount, XmlMemoryAllocator& inAllocator)
{
TDataType* tempData = NULL;
readStridedBufferProperty<TDataType>( ioReader, inPropName, tempData, ioData.stride, outCount, inAllocator );
ioData.data = reinterpret_cast<PxMaterialTableIndex*>( tempData );
}
template<typename TDataType>
inline void readStridedBufferProperty( XmlReader& ioReader, const char* inPropName, PxBoundedData& ioData, XmlMemoryAllocator& inAllocator)
{
return readStridedBufferProperty<TDataType>( ioReader, inPropName, ioData, ioData.count, inAllocator );
}
} }
#endif

View File

@ -0,0 +1,243 @@
//
// 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-2021 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_XML_IMPL_H
#define PX_XML_IMPL_H
#include "SnXmlMemoryPool.h"
#include "PsString.h"
#include "foundation/PxMemory.h"
namespace physx { namespace Sn {
typedef CMemoryPoolManager TMemoryPoolManager;
namespace snXmlImpl {
inline PxU32 strLen( const char* inStr )
{
PxU32 len = 0;
if ( inStr )
{
while ( *inStr )
{
++len;
++inStr;
}
}
return len;
}
}
inline const char* copyStr( PxAllocatorCallback& inAllocator, const char* inStr )
{
if ( inStr && *inStr )
{
PxU32 theLen = snXmlImpl::strLen( inStr );
//The memory will never be released by repx. If you want it released, you need to pass in a custom allocator
//that tracks all allocations and releases unreleased allocations yourself.
char* dest = reinterpret_cast<char* >( inAllocator.allocate( theLen + 1, "Repx::const char*", __FILE__, __LINE__ ) );
PxMemCopy( dest, inStr, theLen );
dest[theLen] = 0;
return dest;
}
return "";
}
template<typename TManagerType>
inline const char* copyStr( TManagerType* inMgr, const char* inStr )
{
if ( inStr && *inStr )
{
PxU32 theLen = snXmlImpl::strLen( inStr );
char* dest = reinterpret_cast<char* >( inMgr->allocate( theLen + 1 ) );
PxMemCopy( dest, inStr, theLen );
dest[theLen] = 0;
return dest;
}
return "";
}
inline void releaseStr( TMemoryPoolManager* inMgr, const char* inStr, PxU32 )
{
if ( inStr && *inStr )
{
inMgr->deallocate( reinterpret_cast< PxU8* >( const_cast<char*>( inStr ) ) );
}
}
inline void releaseStr( TMemoryPoolManager* inMgr, const char* inStr )
{
if ( inStr && *inStr )
{
PxU32 theLen = snXmlImpl::strLen( inStr );
releaseStr( inMgr, inStr, theLen );
}
}
struct XmlNode
{
const char* mName; //Never released until all collections are released
const char* mData; //Never released until all collections are released
XmlNode* mNextSibling;
XmlNode* mPreviousSibling;
XmlNode* mFirstChild;
XmlNode* mParent;
XmlNode( const XmlNode& );
XmlNode& operator=( const XmlNode& );
PX_INLINE void initPtrs()
{
mNextSibling = NULL;
mPreviousSibling = NULL;
mFirstChild = NULL;
mParent = NULL;
}
PX_INLINE XmlNode( const char* inName = "", const char* inData = "" )
: mName( inName )
, mData( inData )
{ initPtrs(); }
void addChild( XmlNode* inItem )
{
inItem->mParent = this;
if ( mFirstChild == NULL )
mFirstChild = inItem;
else
{
XmlNode* theNode = mFirstChild;
//Follow the chain till the end.
while( theNode->mNextSibling != NULL )
theNode = theNode->mNextSibling;
theNode->mNextSibling = inItem;
inItem->mPreviousSibling = theNode;
}
}
PX_INLINE XmlNode* findChildByName( const char* inName )
{
for ( XmlNode* theNode = mFirstChild; theNode; theNode = theNode->mNextSibling )
{
XmlNode* theRepXNode = theNode;
if ( physx::shdfnd::stricmp( theRepXNode->mName, inName ) == 0 )
return theNode;
}
return NULL;
}
PX_INLINE void orphan()
{
if ( mParent )
{
if ( mParent->mFirstChild == this )
mParent->mFirstChild = mNextSibling;
}
if ( mPreviousSibling )
mPreviousSibling->mNextSibling = mNextSibling;
if ( mNextSibling )
mNextSibling->mPreviousSibling = mPreviousSibling;
if ( mFirstChild )
mFirstChild->mParent = NULL;
initPtrs();
}
};
inline XmlNode* allocateRepXNode( TMemoryPoolManager* inManager, const char* inName, const char* inData )
{
XmlNode* retval = inManager->allocate<XmlNode>();
retval->mName = copyStr( inManager, inName );
retval->mData = copyStr( inManager, inData );
return retval;
}
inline void release( TMemoryPoolManager* inManager, XmlNode* inNode )
{
//We *don't* release the strings associated with the node
//because they could be shared. Instead, we just let them 'leak'
//in some sense, at least until the memory manager itself is deleted.
//DO NOT UNCOMMENT THE LINES BELOW!!
//releaseStr( inManager, inNode->mName );
//releaseStr( inManager, inNode->mData );
inManager->deallocate( inNode );
}
static PX_INLINE void releaseNodeAndChildren( TMemoryPoolManager* inManager, XmlNode* inNode )
{
if ( inNode->mFirstChild )
{
XmlNode* childNode( inNode->mFirstChild );
while( childNode )
{
XmlNode* _node( childNode );
childNode = _node->mNextSibling;
releaseNodeAndChildren( inManager, _node );
}
}
inNode->orphan();
release( inManager, inNode );
}
static XmlNode* copyRepXNodeAndSiblings( TMemoryPoolManager* inManager, const XmlNode* inNode, XmlNode* inParent );
static XmlNode* copyRepXNode( TMemoryPoolManager* inManager, const XmlNode* inNode, XmlNode* inParent = NULL )
{
XmlNode* newNode( allocateRepXNode( inManager, NULL, NULL ) );
newNode->mName = inNode->mName; //Some light structural sharing
newNode->mData = inNode->mData; //Some light structural sharing
newNode->mParent = inParent;
if ( inNode->mFirstChild )
newNode->mFirstChild = copyRepXNodeAndSiblings( inManager, inNode->mFirstChild, newNode );
return newNode;
}
static XmlNode* copyRepXNodeAndSiblings( TMemoryPoolManager* inManager, const XmlNode* inNode, XmlNode* inParent )
{
XmlNode* sibling = inNode->mNextSibling;
if ( sibling ) sibling = copyRepXNodeAndSiblings( inManager, sibling, inParent );
XmlNode* newNode = copyRepXNode( inManager, inNode, inParent );
newNode->mNextSibling = sibling;
if ( sibling ) sibling->mPreviousSibling = newNode;
return newNode;
}
inline bool isBigEndian() { int i = 1; return *(reinterpret_cast<char*>(&i))==0; }
struct NameStackEntry
{
const char* mName;
bool mOpen;
NameStackEntry( const char* nm ) : mName( nm ), mOpen( false ) {}
};
typedef PxProfileArray<NameStackEntry> TNameStack;
} }
#endif

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-2021 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_XML_MEMORY_ALLOCATOR_H
#define PX_XML_MEMORY_ALLOCATOR_H
#include "foundation/PxSimpleTypes.h"
namespace physx {
class XmlMemoryAllocator
{
protected:
virtual ~XmlMemoryAllocator(){}
public:
virtual PxU8* allocate(PxU32 inSize) = 0;
virtual void deallocate( PxU8* inMem ) = 0;
virtual PxAllocatorCallback& getAllocator() = 0;
template<typename TObjectType>
TObjectType* allocate()
{
TObjectType* retval = reinterpret_cast< TObjectType* >( allocate( sizeof( TObjectType ) ) );
new (retval) TObjectType();
return retval;
}
template<typename TObjectType, typename TArgType>
TObjectType* allocate(const TArgType &arg)
{
TObjectType* retval = reinterpret_cast< TObjectType* >( allocate( sizeof( TObjectType ) ) );
new (retval) TObjectType(arg);
return retval;
}
template<typename TObjectType>
void deallocate( TObjectType* inObject )
{
deallocate( reinterpret_cast<PxU8*>( inObject ) );
}
template<typename TObjectType>
inline TObjectType* batchAllocate(PxU32 inCount )
{
TObjectType* retval = reinterpret_cast<TObjectType*>( allocate( sizeof(TObjectType) * inCount ) );
for ( PxU32 idx = 0; idx < inCount; ++idx )
{
new (retval + idx) TObjectType();
}
return retval;
}
template<typename TObjectType, typename TArgType>
inline TObjectType* batchAllocate(PxU32 inCount, const TArgType &arg)
{
TObjectType* retval = reinterpret_cast<TObjectType*>( allocate( sizeof(TObjectType) * inCount ) );
for ( PxU32 idx = 0; idx < inCount; ++idx )
{
new (retval + idx) TObjectType(arg);
}
return retval;
}
//Duplicate function definition for gcc.
template<typename TObjectType>
inline TObjectType* batchAllocate(TObjectType*, PxU32 inCount )
{
TObjectType* retval = reinterpret_cast<TObjectType*>( allocate( sizeof(TObjectType) * inCount ) );
for ( PxU32 idx = 0; idx < inCount; ++idx )
{
new (retval + idx) TObjectType();
}
return retval;
}
};
struct XmlMemoryAllocatorImpl : public XmlMemoryAllocator
{
Sn::TMemoryPoolManager mManager;
XmlMemoryAllocatorImpl( PxAllocatorCallback& inAllocator )
: mManager( inAllocator )
{
}
XmlMemoryAllocatorImpl &operator=(const XmlMemoryAllocatorImpl &);
virtual PxAllocatorCallback& getAllocator()
{
return mManager.getWrapper().getAllocator();
}
virtual PxU8* allocate(PxU32 inSize )
{
if ( !inSize )
return NULL;
return mManager.allocate( inSize );
}
virtual void deallocate( PxU8* inMem )
{
if ( inMem )
mManager.deallocate( inMem );
}
};
}
#endif

View File

@ -0,0 +1,373 @@
//
// 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-2021 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_XML_MEMORYPOOL_H
#define PX_XML_MEMORYPOOL_H
#include "foundation/PxAssert.h"
#include "PsArray.h"
#include "PxProfileAllocatorWrapper.h"
namespace physx {
using namespace physx::profile;
/**
* Linked list used to store next node ptr.
*/
struct SMemPoolNode
{
SMemPoolNode* mNextNode;
};
/**
* Template arguments are powers of two.
* A very fast memory pool that is not memory efficient. It contains a vector of pointers
* to blocks of memory along with a linked list of free sections. All sections are
* of the same size so allocating memory is very fast, there isn't a linear search
* through blocks of indeterminate size. It also means there is memory wasted
* when objects aren't sized to powers of two.
*/
template<PxU8 TItemSize
, PxU8 TItemCount >
class CMemoryPool
{
typedef PxProfileArray<PxU8*> TPxU8PtrList;
PxProfileAllocatorWrapper& mWrapper;
TPxU8PtrList mAllMemory;
SMemPoolNode* mFirstFreeNode;
public:
CMemoryPool(PxProfileAllocatorWrapper& inWrapper)
: mWrapper( inWrapper )
, mAllMemory( inWrapper )
, mFirstFreeNode( NULL )
{}
~CMemoryPool()
{
TPxU8PtrList::ConstIterator theEnd = mAllMemory.end();
for ( TPxU8PtrList::ConstIterator theIter = mAllMemory.begin();
theIter != theEnd;
++theIter )
{
PxU8* thePtr = *theIter;
mWrapper.getAllocator().deallocate( thePtr );
}
mAllMemory.clear();
mFirstFreeNode = NULL;
}
//Using deallocated memory to hold the pointers to the next amount of memory.
PxU8* allocate()
{
if ( mFirstFreeNode )
{
PxU8* retval = reinterpret_cast<PxU8*>(mFirstFreeNode);
mFirstFreeNode = mFirstFreeNode->mNextNode;
return retval;
}
PxU32 itemSize = GetItemSize();
PxU32 itemCount = 1 << TItemCount;
//No free nodes, make some more.
PxU8* retval = reinterpret_cast<PxU8*>(mWrapper.getAllocator().allocate( itemCount * itemSize, "RepX fixed-size memory pool", __FILE__, __LINE__ ));
PxU8* dataPtr = retval + itemSize;
//Free extra chunks
for( PxU32 idx = 1; idx < itemCount; ++idx, dataPtr += itemSize )
deallocate( dataPtr );
mAllMemory.pushBack(retval);
return retval;
}
void deallocate( PxU8* inData )
{
SMemPoolNode* nodePtr = reinterpret_cast<SMemPoolNode*>(inData);
nodePtr->mNextNode = mFirstFreeNode;
mFirstFreeNode = nodePtr;
}
//We have to have at least a pointer's worth of memory
inline PxU32 GetItemSize() { return sizeof(SMemPoolNode) << TItemSize; }
};
typedef PxU32 TMemAllocSizeType;
struct SVariableMemPoolNode : SMemPoolNode
{
TMemAllocSizeType mSize;
SVariableMemPoolNode* NextNode() { return static_cast< SVariableMemPoolNode* >( mNextNode ); }
};
/**
* Manages variable sized allocations.
* Keeps track of freed allocations in a insertion sorted
* list. Allocating new memory traverses the list linearly.
* This object will split nodes if the node is more than
* twice as large as the request memory allocation.
*/
class CVariableMemoryPool
{
typedef PxProfileHashMap<TMemAllocSizeType, SVariableMemPoolNode*> TFreeNodeMap;
typedef PxProfileArray<PxU8*> TPxU8PtrList;
PxProfileAllocatorWrapper& mWrapper;
TPxU8PtrList mAllMemory;
TFreeNodeMap mFreeNodeMap;
PxU32 mMinAllocationSize;
CVariableMemoryPool &operator=(const CVariableMemoryPool &);
public:
CVariableMemoryPool(PxProfileAllocatorWrapper& inWrapper, PxU32 inMinAllocationSize = 0x20 )
: mWrapper( inWrapper )
, mAllMemory( inWrapper )
, mFreeNodeMap( inWrapper)
, mMinAllocationSize( inMinAllocationSize )
{}
~CVariableMemoryPool()
{
TPxU8PtrList::ConstIterator theEnd = mAllMemory.end();
for ( TPxU8PtrList::ConstIterator theIter = mAllMemory.begin();
theIter != theEnd;
++theIter )
{
PxU8* thePtr = *theIter;
mWrapper.getAllocator().deallocate( thePtr );
}
mAllMemory.clear();
mFreeNodeMap.clear();
}
PxU8* MarkMem( PxU8* inMem, TMemAllocSizeType inSize )
{
PX_ASSERT( inSize >= sizeof( SVariableMemPoolNode ) );
SVariableMemPoolNode* theMem = reinterpret_cast<SVariableMemPoolNode*>( inMem );
theMem->mSize = inSize;
return reinterpret_cast< PxU8* >( theMem + 1 );
}
//Using deallocated memory to hold the pointers to the next amount of memory.
PxU8* allocate( PxU32 size )
{
//Ensure we can place the size of the memory at the start
//of the memory block.
//Kai: to reduce the size of hash map, the requested size is aligned to 128 bytes
PxU32 theRequestedSize = (size + sizeof(SVariableMemPoolNode) + 127) & ~127;
TFreeNodeMap::Entry* entry = const_cast<TFreeNodeMap::Entry*>( mFreeNodeMap.find( theRequestedSize ) );
if ( NULL != entry )
{
SVariableMemPoolNode* theNode = entry->second;
PX_ASSERT( NULL != theNode );
PX_ASSERT( theNode->mSize == theRequestedSize );
entry->second = theNode->NextNode();
if (entry->second == NULL)
mFreeNodeMap.erase( theRequestedSize );
return reinterpret_cast< PxU8* >( theNode + 1 );
}
if ( theRequestedSize < mMinAllocationSize )
theRequestedSize = mMinAllocationSize;
//No large enough free nodes, make some more.
PxU8* retval = reinterpret_cast<PxU8*>(mWrapper.getAllocator().allocate( size_t(theRequestedSize), "RepX variable sized memory pool", __FILE__, __LINE__ ));
//If we allocated it, we free it.
mAllMemory.pushBack( retval );
return MarkMem( retval, theRequestedSize );
}
//The size is stored at the beginning of the memory block.
void deallocate( PxU8* inData )
{
SVariableMemPoolNode* theData = reinterpret_cast< SVariableMemPoolNode* >( inData ) - 1;
TMemAllocSizeType theSize = theData->mSize;
AddFreeMem( reinterpret_cast< PxU8* >( theData ), theSize );
}
void CheckFreeListInvariant( SVariableMemPoolNode* inNode )
{
if ( inNode && inNode->mNextNode )
{
PX_ASSERT( inNode->mSize <= inNode->NextNode()->mSize );
}
}
void AddFreeMem( PxU8* inMemory, TMemAllocSizeType inSize )
{
PX_ASSERT( inSize >= sizeof( SVariableMemPoolNode ) );
SVariableMemPoolNode* theNewNode = reinterpret_cast< SVariableMemPoolNode* >( inMemory );
theNewNode->mNextNode = NULL;
theNewNode->mSize = inSize;
TFreeNodeMap::Entry* entry = const_cast<TFreeNodeMap::Entry*>( mFreeNodeMap.find( inSize ) );
if (NULL != entry)
{
theNewNode->mNextNode = entry->second;
entry->second = theNewNode;
}
else
{
mFreeNodeMap.insert( inSize, theNewNode );
}
}
};
/**
* The manager keeps a list of memory pools for different sizes of allocations.
* Anything too large simply gets allocated using the new operator.
* This doesn't mark the memory with the size of the allocated memory thus
* allowing much more efficient allocation of small items. For large enough
* allocations, it does mark the size.
*
* When using as a general memory manager, you need to wrap this class with
* something that actually does mark the returned allocation with the size
* of the allocation.
*/
class CMemoryPoolManager
{
CMemoryPoolManager &operator=(const CMemoryPoolManager &);
public:
PxProfileAllocatorWrapper mWrapper;
//CMemoryPool<0,8> m0ItemPool;
//CMemoryPool<1,8> m1ItemPool;
//CMemoryPool<2,8> m2ItemPool;
//CMemoryPool<3,8> m3ItemPool;
//CMemoryPool<4,8> m4ItemPool;
//CMemoryPool<5,8> m5ItemPool;
//CMemoryPool<6,8> m6ItemPool;
//CMemoryPool<7,8> m7ItemPool;
//CMemoryPool<8,8> m8ItemPool;
CVariableMemoryPool mVariablePool;
CMemoryPoolManager( PxAllocatorCallback& inAllocator )
: mWrapper( inAllocator )
//, m0ItemPool( mWrapper )
//, m1ItemPool( mWrapper )
//, m2ItemPool( mWrapper )
//, m3ItemPool( mWrapper )
//, m4ItemPool( mWrapper )
//, m5ItemPool( mWrapper )
//, m6ItemPool( mWrapper )
//, m7ItemPool( mWrapper )
//, m8ItemPool( mWrapper )
, mVariablePool( mWrapper )
{
}
PxProfileAllocatorWrapper& getWrapper() { return mWrapper; }
inline PxU8* allocate( PxU32 inSize )
{
/*
if ( inSize <= m0ItemPool.GetItemSize() )
return m0ItemPool.allocate();
if ( inSize <= m1ItemPool.GetItemSize() )
return m1ItemPool.allocate();
if ( inSize <= m2ItemPool.GetItemSize() )
return m2ItemPool.allocate();
if ( inSize <= m3ItemPool.GetItemSize() )
return m3ItemPool.allocate();
if ( inSize <= m4ItemPool.GetItemSize() )
return m4ItemPool.allocate();
if ( inSize <= m5ItemPool.GetItemSize() )
return m5ItemPool.allocate();
if ( inSize <= m6ItemPool.GetItemSize() )
return m6ItemPool.allocate();
if ( inSize <= m7ItemPool.GetItemSize() )
return m7ItemPool.allocate();
if ( inSize <= m8ItemPool.GetItemSize() )
return m8ItemPool.allocate();
*/
return mVariablePool.allocate( inSize );
}
inline void deallocate( PxU8* inMemory )
{
if ( inMemory == NULL )
return;
/*
if ( inSize <= m0ItemPool.GetItemSize() )
m0ItemPool.deallocate(inMemory);
else if ( inSize <= m1ItemPool.GetItemSize() )
m1ItemPool.deallocate(inMemory);
else if ( inSize <= m2ItemPool.GetItemSize() )
m2ItemPool.deallocate(inMemory);
else if ( inSize <= m3ItemPool.GetItemSize() )
m3ItemPool.deallocate(inMemory);
else if ( inSize <= m4ItemPool.GetItemSize() )
m4ItemPool.deallocate(inMemory);
else if ( inSize <= m5ItemPool.GetItemSize() )
m5ItemPool.deallocate(inMemory);
else if ( inSize <= m6ItemPool.GetItemSize() )
m6ItemPool.deallocate(inMemory);
else if ( inSize <= m7ItemPool.GetItemSize() )
m7ItemPool.deallocate(inMemory);
else if ( inSize <= m8ItemPool.GetItemSize() )
m8ItemPool.deallocate(inMemory);
else
*/
mVariablePool.deallocate(inMemory);
}
/**
* allocate an object. Calls constructor on the new memory.
*/
template<typename TObjectType>
inline TObjectType* allocate()
{
TObjectType* retval = reinterpret_cast<TObjectType*>( allocate( sizeof(TObjectType) ) );
new (retval)TObjectType();
return retval;
}
/**
* deallocate an object calling the destructor on the object.
* This *must* be the concrete type, it cannot be a generic type.
*/
template<typename TObjectType>
inline void deallocate( TObjectType* inObject )
{
inObject->~TObjectType();
deallocate( reinterpret_cast<PxU8*>(inObject) );
}
/**
* allocate an object. Calls constructor on the new memory.
*/
template<typename TObjectType>
inline TObjectType* BatchAllocate(PxU32 inCount )
{
TObjectType* retval = reinterpret_cast<TObjectType*>( allocate( sizeof(TObjectType) * inCount ) );
return retval;
}
/**
* deallocate an object calling the destructor on the object.
* This *must* be the concrete type, it cannot be a generic type.
*/
template<typename TObjectType>
inline void BatchDeallocate( TObjectType* inObject, PxU32 inCount )
{
PX_UNUSED(inCount);
deallocate( reinterpret_cast<PxU8*>(inObject) );
}
};
}
#endif

View File

@ -0,0 +1,173 @@
//
// 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-2021 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_XML_MEMORY_POOL_STREAMS_H
#define PX_XML_MEMORY_POOL_STREAMS_H
#include "foundation/PxTransform.h"
#include "foundation/PxIO.h"
#include "SnXmlMemoryPool.h"
#include "CmPhysXCommon.h"
namespace physx {
template<typename TDataType>
struct XmlDefaultValue
{
bool force_compile_error;
};
#define XML_DEFINE_DEFAULT_VALUE(type, defVal ) \
template<> \
struct XmlDefaultValue<type> \
{ \
type getDefaultValue() { return type(defVal); } \
};
XML_DEFINE_DEFAULT_VALUE(PxU8, 0)
XML_DEFINE_DEFAULT_VALUE(PxI8, 0)
XML_DEFINE_DEFAULT_VALUE(PxU16, 0)
XML_DEFINE_DEFAULT_VALUE(PxI16, 0)
XML_DEFINE_DEFAULT_VALUE(PxU32, 0)
XML_DEFINE_DEFAULT_VALUE(PxI32, 0)
XML_DEFINE_DEFAULT_VALUE(PxU64, 0)
XML_DEFINE_DEFAULT_VALUE(PxI64, 0)
XML_DEFINE_DEFAULT_VALUE(PxF32, 0)
XML_DEFINE_DEFAULT_VALUE(PxF64, 0)
#undef XML_DEFINE_DEFAULT_VALUE
template<>
struct XmlDefaultValue<PxVec3>
{
PxVec3 getDefaultValue() { return PxVec3( 0,0,0 ); }
};
template<>
struct XmlDefaultValue<PxTransform>
{
PxTransform getDefaultValue() { return PxTransform(PxIdentity); }
};
template<>
struct XmlDefaultValue<PxQuat>
{
PxQuat getDefaultValue() { return PxQuat(PxIdentity); }
};
/**
* Mapping of PxOutputStream to a memory pool manager.
* Allows write-then-read semantics of a set of
* data. Can safely write up to 4GB of data; then you
* will silently fail...
*/
template<typename TAllocatorType>
struct MemoryBufferBase : public PxOutputStream, public PxInputStream
{
TAllocatorType* mManager;
mutable PxU32 mWriteOffset;
mutable PxU32 mReadOffset;
PxU8* mBuffer;
PxU32 mCapacity;
MemoryBufferBase( TAllocatorType* inManager )
: mManager( inManager )
, mWriteOffset( 0 )
, mReadOffset( 0 )
, mBuffer( NULL )
, mCapacity( 0 )
{
}
virtual ~MemoryBufferBase()
{
mManager->deallocate( mBuffer );
}
PxU8* releaseBuffer()
{
clear();
mCapacity = 0;
PxU8* retval(mBuffer);
mBuffer = NULL;
return retval;
}
void clear()
{
mWriteOffset = mReadOffset = 0;
}
virtual PxU32 read(void* dest, PxU32 count)
{
bool fits = ( mReadOffset + count ) <= mWriteOffset;
PX_ASSERT( fits );
if ( fits )
{
PxMemCopy( dest, mBuffer + mReadOffset, count );
mReadOffset += count;
return count;
}
return 0;
}
inline void checkCapacity( PxU32 inNewCapacity )
{
if ( mCapacity < inNewCapacity )
{
PxU32 newCapacity = 32;
while( newCapacity < inNewCapacity )
newCapacity = newCapacity << 1;
PxU8* newData( mManager->allocate( newCapacity ) );
if ( mWriteOffset )
PxMemCopy( newData, mBuffer, mWriteOffset );
mManager->deallocate( mBuffer );
mBuffer = newData;
mCapacity = newCapacity;
}
}
virtual PxU32 write(const void* src, PxU32 count)
{
checkCapacity( mWriteOffset + count );
PxMemCopy( mBuffer + mWriteOffset, src, count );
mWriteOffset += count;
return count;
}
};
class MemoryBuffer : public MemoryBufferBase<CMemoryPoolManager >
{
public:
MemoryBuffer( CMemoryPoolManager* inManager ) : MemoryBufferBase<CMemoryPoolManager >( inManager ) {}
};
}
#endif

View File

@ -0,0 +1,130 @@
//
// 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-2021 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_XML_READER_H
#define PX_XML_READER_H
#include "foundation/PxSimpleTypes.h"
#include "extensions/PxRepXSimpleType.h"
namespace physx {
namespace Sn { struct XmlNode; }
/**
* Reader used to read data out of the repx format.
*/
class XmlReader
{
protected:
virtual ~XmlReader(){}
public:
/** Read a key-value pair out of the database */
virtual bool read( const char* inName, const char*& outData ) = 0;
/** Read an object id out of the database */
virtual bool read( const char* inName, PxSerialObjectId& outId ) = 0;
/** Goto a child element by name. That child becomes this reader's context */
virtual bool gotoChild( const char* inName ) = 0;
/** Goto the first child regardless of name */
virtual bool gotoFirstChild() = 0;
/** Goto the next sibling regardless of name */
virtual bool gotoNextSibling() = 0;
/** Count all children of the current object */
virtual PxU32 countChildren() = 0;
/** Get the name of the current item */
virtual const char* getCurrentItemName() = 0;
/** Get the value of the current item */
virtual const char* getCurrentItemValue() = 0;
/** Leave the current child */
virtual bool leaveChild() = 0;
/** Get reader for the parental object */
virtual XmlReader* getParentReader() = 0;
/**
* Ensures we don't leave the reader in an odd state
* due to not leaving a given child
*/
virtual void pushCurrentContext() = 0;
/** Pop the current context back to where it during push*/
virtual void popCurrentContext() = 0;
};
//Used when upgrading a repx collection
class XmlReaderWriter : public XmlReader
{
public:
//Clears the stack of nodes (push/pop current node reset)
//and sets the current node to inNode.
virtual void setNode( Sn::XmlNode& node ) = 0;
//If the child exists, add it.
//the either way goto that child.
virtual void addOrGotoChild( const char* name ) = 0;
//Value is copied into the collection, inValue has no further references
//to it.
virtual void setCurrentItemValue( const char* value ) = 0;
//Removes the child but does not release the char* name or char* data ptrs.
//Those pointers are never released and are shared among collections.
//Thus copying nodes is cheap and safe.
virtual bool removeChild( const char* name ) = 0;
virtual void release() = 0;
bool renameProperty( const char* oldName, const char* newName )
{
if ( gotoChild( oldName ) )
{
const char* value = getCurrentItemValue();
leaveChild();
removeChild( oldName );
addOrGotoChild( newName );
setCurrentItemValue( value );
leaveChild();
return true;
}
return false;
}
bool readAndRemoveProperty( const char* name, const char*& outValue )
{
bool retval = read( name, outValue );
if ( retval ) removeChild( name );
return retval;
}
bool writePropertyIfNotEmpty( const char* name, const char* value )
{
if ( value && *value )
{
addOrGotoChild( name );
setCurrentItemValue( value );
leaveChild();
return true;
}
return false;
}
};
}
#endif

View File

@ -0,0 +1,834 @@
//
// 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-2021 NVIDIA Corporation. All rights reserved.
// Copyright (c) 2004-2008 AGEIA Technologies, Inc. All rights reserved.
// Copyright (c) 2001-2004 NovodeX AG. All rights reserved.
#include "SnXmlImpl.h"
#include "PsHash.h"
#include "PsHashMap.h"
#include "SnSimpleXmlWriter.h"
#include "PsSort.h"
#include "PsFastXml.h"
#include "PsString.h"
#include "SnXmlMemoryPool.h"
#include "PxExtensionMetaDataObjects.h"
#include "SnXmlVisitorWriter.h"
#include "SnXmlVisitorReader.h"
#include "SnXmlMemoryAllocator.h"
#include "SnXmlStringToType.h"
#include "PsString.h"
#include "SnRepXCollection.h"
#include "SnRepXUpgrader.h"
#include "../SnSerializationRegistry.h"
#include "PsFoundation.h"
#include "CmCollection.h"
using namespace physx;
using namespace Sn;
using namespace physx::profile; //for the foundation wrapper system.
namespace physx { namespace Sn {
class XmlNodeWriter : public SimpleXmlWriter
{
XmlMemoryAllocatorImpl& mParseAllocator;
XmlNode* mCurrentNode;
XmlNode* mTopNode;
PxU32 mTabCount;
public:
XmlNodeWriter( XmlMemoryAllocatorImpl& inAllocator, PxU32 inTabCount = 0 )
: mParseAllocator( inAllocator )
, mCurrentNode( NULL )
, mTopNode( NULL )
, mTabCount( inTabCount )
{}
XmlNodeWriter& operator=(const XmlNodeWriter&);
virtual ~XmlNodeWriter(){}
void onNewNode( XmlNode* newNode )
{
if ( mCurrentNode != NULL )
mCurrentNode->addChild( newNode );
if ( mTopNode == NULL )
mTopNode = newNode;
mCurrentNode = newNode;
++mTabCount;
}
XmlNode* getTopNode() const { return mTopNode; }
virtual void beginTag( const char* inTagname )
{
onNewNode( allocateRepXNode( &mParseAllocator.mManager, inTagname, NULL ) );
}
virtual void endTag()
{
if ( mCurrentNode )
mCurrentNode = mCurrentNode->mParent;
if ( mTabCount )
--mTabCount;
}
virtual void addAttribute( const char*, const char* )
{
PX_ASSERT( false );
}
virtual void writeContentTag( const char* inTag, const char* inContent )
{
onNewNode( allocateRepXNode( &mParseAllocator.mManager, inTag, inContent ) );
endTag();
}
virtual void addContent( const char* inContent )
{
if ( mCurrentNode->mData )
releaseStr( &mParseAllocator.mManager, mCurrentNode->mData );
mCurrentNode->mData = copyStr( &mParseAllocator.mManager, inContent );
}
virtual PxU32 tabCount() { return mTabCount; }
};
struct XmlWriterImpl : public XmlWriter
{
PxU32 mTagDepth;
SimpleXmlWriter* mWriter;
MemoryBuffer* mMemBuffer;
XmlWriterImpl( SimpleXmlWriter* inWriter, MemoryBuffer* inMemBuffer )
: mTagDepth( 0 )
, mWriter( inWriter )
, mMemBuffer( inMemBuffer )
{
}
~XmlWriterImpl()
{
while( mTagDepth )
{
--mTagDepth;
mWriter->endTag();
}
}
virtual void write( const char* inName, const char* inData )
{
mWriter->writeContentTag( inName, inData );
}
virtual void write( const char* inName, const PxRepXObject& inLiveObject )
{
(*mMemBuffer) << inLiveObject.id;
writeProperty( *mWriter, *mMemBuffer, inName );
}
virtual void addAndGotoChild( const char* inName )
{
mWriter->beginTag( inName );
mTagDepth++;
}
virtual void leaveChild()
{
if ( mTagDepth )
{
mWriter->endTag();
--mTagDepth;
}
}
};
struct XmlParseArgs
{
XmlMemoryAllocatorImpl* mAllocator;
PxProfileArray<RepXCollectionItem>* mCollection;
XmlParseArgs( XmlMemoryAllocatorImpl* inAllocator
, PxProfileArray<RepXCollectionItem>* inCollection)
: mAllocator( inAllocator )
, mCollection( inCollection )
{
}
};
struct XmlNodeReader : public XmlReaderWriter
{
PxProfileAllocatorWrapper mWrapper;
CMemoryPoolManager& mManager;
XmlNode* mCurrentNode;
XmlNode* mTopNode;
PxProfileArray<XmlNode*> mContext;
XmlNodeReader( XmlNode* inCurrentNode, PxAllocatorCallback& inAllocator, CMemoryPoolManager& nodePoolManager )
: mWrapper( inAllocator )
, mManager( nodePoolManager )
, mCurrentNode( inCurrentNode )
, mTopNode( inCurrentNode )
, mContext( mWrapper )
{
}
//Does this node exist as data in the format.
virtual bool read( const char* inName, const char*& outData )
{
XmlNode* theChild( mCurrentNode->findChildByName( inName ) );
if ( theChild )
{
outData = theChild->mData;
return outData && *outData;
}
return false;
}
virtual bool read( const char* inName, PxSerialObjectId& outId )
{
XmlNode* theChild( mCurrentNode->findChildByName( inName ) );
if ( theChild )
{
const char* theValue( theChild->mData );
strto( outId, theValue );
return true;
}
return false;
}
virtual bool gotoChild( const char* inName )
{
XmlNode* theChild( mCurrentNode->findChildByName( inName ) );
if ( theChild )
{
mCurrentNode =theChild;
return true;
}
return false;
}
virtual bool gotoFirstChild()
{
if ( mCurrentNode->mFirstChild )
{
mCurrentNode = mCurrentNode->mFirstChild;
return true;
}
return false;
}
virtual bool gotoNextSibling()
{
if ( mCurrentNode->mNextSibling )
{
mCurrentNode = mCurrentNode->mNextSibling;
return true;
}
return false;
}
virtual PxU32 countChildren()
{
PxU32 retval= 0;
for ( XmlNode* theChild = mCurrentNode->mFirstChild; theChild != NULL; theChild = theChild->mNextSibling )
++retval;
return retval;
}
virtual const char* getCurrentItemName()
{
return mCurrentNode->mName;
}
virtual const char* getCurrentItemValue()
{
return mCurrentNode->mData;
}
virtual bool leaveChild()
{
if ( mCurrentNode != mTopNode && mCurrentNode->mParent )
{
mCurrentNode = mCurrentNode->mParent;
return true;
}
return false;
}
virtual void pushCurrentContext()
{
mContext.pushBack( mCurrentNode );
}
virtual void popCurrentContext()
{
if ( mContext.size() )
{
mCurrentNode = mContext.back();
mContext.popBack();
}
}
virtual void setNode( XmlNode& inNode )
{
mContext.clear();
mCurrentNode = &inNode;
mTopNode = mCurrentNode;
}
virtual XmlReader* getParentReader()
{
XmlReader* retval = PX_PLACEMENT_NEW((mWrapper.getAllocator().allocate(sizeof(XmlNodeReader), "createNodeEditor", __FILE__, __LINE__ )), XmlNodeReader)
( mTopNode, mWrapper.getAllocator(), mManager );
return retval;
}
virtual void addOrGotoChild( const char* inName )
{
if ( gotoChild( inName )== false )
{
XmlNode* newNode = allocateRepXNode( &mManager, inName, NULL );
mCurrentNode->addChild( newNode );
mCurrentNode = newNode;
}
}
virtual void setCurrentItemValue( const char* inValue )
{
mCurrentNode->mData = copyStr( &mManager, inValue );
}
virtual bool removeChild( const char* name )
{
XmlNode* theChild( mCurrentNode->findChildByName( name ) );
if ( theChild )
{
releaseNodeAndChildren( &mManager, theChild );
return true;
}
return false;
}
virtual void release() { this->~XmlNodeReader(); mWrapper.getAllocator().deallocate(this); }
private:
XmlNodeReader& operator=(const XmlNodeReader&);
};
PX_INLINE void freeNodeAndChildren( XmlNode* tempNode, TMemoryPoolManager& inManager )
{
for( XmlNode* theNode = tempNode->mFirstChild; theNode != NULL; theNode = theNode->mNextSibling )
freeNodeAndChildren( theNode, inManager );
tempNode->orphan();
release( &inManager, tempNode );
}
class XmlParser : public Ps::FastXml::Callback
{
XmlParseArgs mParseArgs;
//For parse time only allocations
XmlMemoryAllocatorImpl& mParseAllocator;
XmlNode* mCurrentNode;
XmlNode* mTopNode;
public:
XmlParser( XmlParseArgs inArgs, XmlMemoryAllocatorImpl& inParseAllocator )
: mParseArgs( inArgs )
, mParseAllocator( inParseAllocator )
, mCurrentNode( NULL )
, mTopNode( NULL )
{
}
virtual ~XmlParser(){}
virtual bool processComment(const char* /*comment*/) { return true; }
// 'element' is the name of the element that is being closed.
// depth is the recursion depth of this element.
// Return true to continue processing the XML file.
// Return false to stop processing the XML file; leaves the read pointer of the stream right after this close tag.
// The bool 'isError' indicates whether processing was stopped due to an error, or intentionally canceled early.
virtual bool processClose(const char* /*element*/,physx::PxU32 /*depth*/,bool& /*isError*/)
{
mCurrentNode = mCurrentNode->mParent;
return true;
}
// return true to continue processing the XML document, false to skip.
virtual bool processElement(
const char *elementName, // name of the element
const char *elementData, // element data, null if none
const Ps::FastXml::AttributePairs& attr, // attributes
PxI32 /*lineno*/)
{
XmlNode* newNode = allocateRepXNode( &mParseAllocator.mManager, elementName, elementData );
if ( mCurrentNode )
mCurrentNode->addChild( newNode );
mCurrentNode = newNode;
//Add the elements as children.
for( PxI32 item = 0; item < attr.getNbAttr(); item ++ )
{
XmlNode* node = allocateRepXNode( &mParseAllocator.mManager, attr.getKey(PxU32(item)), attr.getValue(PxU32(item)) );
mCurrentNode->addChild( node );
}
if ( mTopNode == NULL ) mTopNode = newNode;
return true;
}
XmlNode* getTopNode() { return mTopNode; }
virtual void * allocate(PxU32 size)
{
if ( size )
return mParseAllocator.allocate(size);
return NULL;
}
virtual void deallocate(void *mem)
{
if ( mem )
mParseAllocator.deallocate(reinterpret_cast<PxU8*>(mem));
}
private:
XmlParser& operator=(const XmlParser&);
};
struct RepXCollectionSharedData
{
PxProfileAllocatorWrapper mWrapper;
XmlMemoryAllocatorImpl mAllocator;
PxU32 mRefCount;
RepXCollectionSharedData( PxAllocatorCallback& inAllocator )
: mWrapper( inAllocator )
, mAllocator( inAllocator )
, mRefCount( 0 )
{
}
~RepXCollectionSharedData() {}
void addRef() { ++mRefCount;}
void release()
{
if ( mRefCount ) --mRefCount;
if ( !mRefCount ) { this->~RepXCollectionSharedData(); mWrapper.getAllocator().deallocate(this);}
}
};
struct SharedDataPtr
{
RepXCollectionSharedData* mData;
SharedDataPtr( RepXCollectionSharedData* inData )
: mData( inData )
{
mData->addRef();
}
SharedDataPtr( const SharedDataPtr& inOther )
: mData( inOther.mData )
{
mData->addRef();
}
SharedDataPtr& operator=( const SharedDataPtr& inOther );
~SharedDataPtr()
{
mData->release();
mData = NULL;
}
RepXCollectionSharedData* operator->() { return mData; }
const RepXCollectionSharedData* operator->() const { return mData; }
};
class RepXCollectionImpl : public RepXCollection, public Ps::UserAllocated
{
SharedDataPtr mSharedData;
XmlMemoryAllocatorImpl& mAllocator;
PxSerializationRegistry& mSerializationRegistry;
PxProfileArray<RepXCollectionItem> mCollection;
TMemoryPoolManager mSerializationManager;
MemoryBuffer mPropertyBuffer;
PxTolerancesScale mScale;
PxVec3 mUpVector;
const char* mVersionStr;
PxCollection* mPxCollection;
public:
RepXCollectionImpl( PxSerializationRegistry& inRegistry, PxAllocatorCallback& inAllocator, PxCollection& inPxCollection )
: mSharedData( &PX_NEW_REPX_SERIALIZER( RepXCollectionSharedData ))
, mAllocator( mSharedData->mAllocator )
, mSerializationRegistry( inRegistry )
, mCollection( mSharedData->mWrapper )
, mSerializationManager( inAllocator )
, mPropertyBuffer( &mSerializationManager )
, mUpVector( 0,0,0 )
, mVersionStr( getLatestVersion() )
, mPxCollection( &inPxCollection )
{
memset( &mScale, 0, sizeof( PxTolerancesScale ) );
PX_ASSERT( mScale.isValid() == false );
}
RepXCollectionImpl( PxSerializationRegistry& inRegistry, const RepXCollectionImpl& inSrc, const char* inNewVersion )
: mSharedData( inSrc.mSharedData )
, mAllocator( mSharedData->mAllocator )
, mSerializationRegistry( inRegistry )
, mCollection( mSharedData->mWrapper )
, mSerializationManager( mSharedData->mWrapper.getAllocator() )
, mPropertyBuffer( &mSerializationManager )
, mScale( inSrc.mScale )
, mUpVector( inSrc.mUpVector )
, mVersionStr( inNewVersion )
, mPxCollection( NULL )
{
}
virtual ~RepXCollectionImpl()
{
PxU32 numItems = mCollection.size();
for ( PxU32 idx = 0; idx < numItems; ++idx )
{
XmlNode* theNode = mCollection[idx].descriptor;
releaseNodeAndChildren( &mAllocator.mManager, theNode );
}
}
RepXCollectionImpl& operator=(const RepXCollectionImpl&);
virtual void destroy()
{
PxProfileAllocatorWrapper tempWrapper( mSharedData->mWrapper.getAllocator() );
this->~RepXCollectionImpl();
tempWrapper.getAllocator().deallocate(this);
}
virtual void setTolerancesScale(const PxTolerancesScale& inScale) { mScale = inScale; }
virtual PxTolerancesScale getTolerancesScale() const { return mScale; }
virtual void setUpVector( const PxVec3& inUpVector ) { mUpVector = inUpVector; }
virtual PxVec3 getUpVector() const { return mUpVector; }
PX_INLINE RepXCollectionItem findItemBySceneItem( const PxRepXObject& inObject ) const
{
//See if the object is in the collection
for ( PxU32 idx =0; idx < mCollection.size(); ++idx )
if ( mCollection[idx].liveObject.serializable == inObject.serializable )
return mCollection[idx];
return RepXCollectionItem();
}
virtual RepXAddToCollectionResult addRepXObjectToCollection( const PxRepXObject& inObject, PxCollection* inCollection, PxRepXInstantiationArgs& inArgs )
{
PX_ASSERT( inObject.serializable );
PX_ASSERT( inObject.id );
if ( inObject.serializable == NULL || inObject.id == 0 )
return RepXAddToCollectionResult( RepXAddToCollectionResult::InvalidParameters );
PxRepXSerializer* theSerializer = mSerializationRegistry.getRepXSerializer( inObject.typeName );
if ( theSerializer == NULL )
return RepXAddToCollectionResult( RepXAddToCollectionResult::SerializerNotFound );
RepXCollectionItem existing = findItemBySceneItem( inObject );
if ( existing.liveObject.serializable )
return RepXAddToCollectionResult( RepXAddToCollectionResult::AlreadyInCollection, existing.liveObject.id );
XmlNodeWriter theXmlWriter( mAllocator, 1 );
XmlWriterImpl theRepXWriter( &theXmlWriter, &mPropertyBuffer );
{
SimpleXmlWriter::STagWatcher theWatcher( theXmlWriter, inObject.typeName );
writeProperty( theXmlWriter, mPropertyBuffer, "Id", inObject.id );
theSerializer->objectToFile( inObject, inCollection, theRepXWriter, mPropertyBuffer,inArgs );
}
mCollection.pushBack( RepXCollectionItem( inObject, theXmlWriter.getTopNode() ) );
return RepXAddToCollectionResult( RepXAddToCollectionResult::Success, inObject.id );
}
virtual bool instantiateCollection( PxRepXInstantiationArgs& inArgs, PxCollection& inCollection )
{
for ( PxU32 idx =0; idx < mCollection.size(); ++idx )
{
RepXCollectionItem theItem( mCollection[idx] );
PxRepXSerializer* theSerializer = mSerializationRegistry.getRepXSerializer( theItem.liveObject.typeName );
if (theSerializer )
{
XmlNodeReader theReader( theItem.descriptor, mAllocator.getAllocator(), mAllocator.mManager );
XmlMemoryAllocatorImpl instantiationAllocator( mAllocator.getAllocator() );
PxRepXObject theLiveObject = theSerializer->fileToObject( theReader, instantiationAllocator, inArgs, &inCollection );
if (theLiveObject.isValid())
{
const PxBase* s = reinterpret_cast<const PxBase*>( theLiveObject.serializable ) ;
inCollection.add( *const_cast<PxBase*>(s), PxSerialObjectId( theItem.liveObject.id ));
}
else
return false;
}
else
{
Ps::getFoundation().error(PxErrorCode::eINTERNAL_ERROR, __FILE__, __LINE__,
"PxSerialization::createCollectionFromXml: "
"PxRepXSerializer missing for type %s", theItem.liveObject.typeName);
return false;
}
}
return true;
}
void saveXmlNode( XmlNode* inNode, SimpleXmlWriter& inWriter )
{
XmlNode* theNode( inNode );
if ( theNode->mData && *theNode->mData && theNode->mFirstChild == NULL )
inWriter.writeContentTag( theNode->mName, theNode->mData );
else
{
inWriter.beginTag( theNode->mName );
if ( theNode->mData && *theNode->mData )
inWriter.addContent( theNode->mData );
for ( XmlNode* theChild = theNode->mFirstChild;
theChild != NULL;
theChild = theChild->mNextSibling )
saveXmlNode( theChild, inWriter );
inWriter.endTag();
}
}
virtual void save( PxOutputStream& inStream )
{
SimpleXmlWriterImpl<PxOutputStream> theWriter( inStream, mAllocator.getAllocator() );
theWriter.beginTag( "PhysXCollection" );
theWriter.addAttribute( "version", mVersionStr );
{
XmlWriterImpl theRepXWriter( &theWriter, &mPropertyBuffer );
writeProperty( theWriter, mPropertyBuffer, "UpVector", mUpVector );
theRepXWriter.addAndGotoChild( "Scale" );
writeAllProperties( &mScale, theRepXWriter, mPropertyBuffer, *mPxCollection);
theRepXWriter.leaveChild();
}
for ( PxU32 idx =0; idx < mCollection.size(); ++idx )
{
RepXCollectionItem theItem( mCollection[idx] );
XmlNode* theNode( theItem.descriptor );
saveXmlNode( theNode, theWriter );
}
}
void load( PxInputData& inFileBuf, SerializationRegistry& s )
{
inFileBuf.seek(0);
XmlParser theParser( XmlParseArgs( &mAllocator, &mCollection ), mAllocator );
Ps::FastXml* theFastXml = Ps::createFastXml( &theParser );
theFastXml->processXml( inFileBuf );
XmlNode* theTopNode = theParser.getTopNode();
if ( theTopNode != NULL )
{
{
XmlMemoryAllocatorImpl instantiationAllocator( mAllocator.getAllocator() );
XmlNodeReader theReader( theTopNode, mAllocator.getAllocator(), mAllocator.mManager );
readProperty( theReader, "UpVector", mUpVector );
if ( theReader.gotoChild( "Scale" ) )
{
readAllProperties( PxRepXInstantiationArgs( s.getPhysics() ), theReader, &mScale, instantiationAllocator, *mPxCollection);
theReader.leaveChild();
}
const char* verStr = NULL;
if ( theReader.read( "version", verStr ) )
mVersionStr = verStr;
}
for ( XmlNode* theChild = theTopNode->mFirstChild;
theChild != NULL;
theChild = theChild->mNextSibling )
{
if ( physx::shdfnd::stricmp( theChild->mName, "scale" ) == 0
|| physx::shdfnd::stricmp( theChild->mName, "version" ) == 0
|| physx::shdfnd::stricmp( theChild->mName, "upvector" ) == 0 )
continue;
XmlNodeReader theReader( theChild, mAllocator.getAllocator(), mAllocator.mManager );
PxRepXObject theObject;
theObject.typeName = theChild->mName;
theObject.serializable = NULL;
PxSerialObjectId theId = 0;
theReader.read( "Id", theId );
theObject.id = theId;
mCollection.pushBack( RepXCollectionItem( theObject, theChild ) );
}
}
else
{
Ps::getFoundation().error(PxErrorCode::eDEBUG_WARNING, __FILE__, __LINE__,
"Cannot parse any object from the input buffer, please check the input repx data.");
}
theFastXml->release();
}
virtual const char* getVersion() { return mVersionStr; }
virtual const RepXCollectionItem* begin() const
{
return mCollection.begin();
}
virtual const RepXCollectionItem* end() const
{
return mCollection.end();
}
virtual RepXCollection& createCollection( const char* inVersionStr )
{
PxAllocatorCallback& allocator = mSharedData->mWrapper.getAllocator();
RepXCollectionImpl* retval = PX_PLACEMENT_NEW((allocator.allocate(sizeof(RepXCollectionImpl), "createCollection", __FILE__, __LINE__ )), RepXCollectionImpl) ( mSerializationRegistry, *this, inVersionStr );
return *retval;
}
//Performs a deep copy of the repx node.
virtual XmlNode* copyRepXNode( const XmlNode* srcNode )
{
return physx::Sn::copyRepXNode( &mAllocator.mManager, srcNode );
}
virtual void addCollectionItem( RepXCollectionItem inItem )
{
mCollection.pushBack( inItem );
}
virtual PxAllocatorCallback& getAllocator() { return mSharedData->mAllocator.getAllocator(); }
//Create a new repx node with this name. Its value is unset.
virtual XmlNode& createRepXNode( const char* name )
{
XmlNode* newNode = allocateRepXNode( &mSharedData->mAllocator.mManager, name, NULL );
return *newNode;
}
//Release this when finished.
virtual XmlReaderWriter& createNodeEditor()
{
PxAllocatorCallback& allocator = mSharedData->mWrapper.getAllocator();
XmlReaderWriter* retval = PX_PLACEMENT_NEW((allocator.allocate(sizeof(XmlNodeReader), "createNodeEditor", __FILE__, __LINE__ )), XmlNodeReader) ( NULL, allocator, mAllocator.mManager );
return *retval;
}
};
const char* RepXCollection::getLatestVersion()
{
#define TOSTR_(x) #x
#define CONCAT_(a, b, c) TOSTR_(a.##b.##c)
#define MAKE_VERSION_STR(a,b,c) CONCAT_(a, b, c)
return MAKE_VERSION_STR(PX_PHYSICS_VERSION_MAJOR,PX_PHYSICS_VERSION_MINOR,PX_PHYSICS_VERSION_BUGFIX);
}
static RepXCollection* create(SerializationRegistry& s, PxAllocatorCallback& inAllocator, PxCollection& inCollection )
{
return PX_PLACEMENT_NEW((inAllocator.allocate(sizeof(RepXCollectionImpl), "RepXCollection::create", __FILE__, __LINE__ )), RepXCollectionImpl) ( s, inAllocator, inCollection );
}
static RepXCollection* create(SerializationRegistry& s, PxInputData &data, PxAllocatorCallback& inAllocator, PxCollection& inCollection )
{
RepXCollectionImpl* theCollection = static_cast<RepXCollectionImpl*>( create(s, inAllocator, inCollection ) );
theCollection->load( data, s );
return theCollection;
}
}
bool PxSerialization::serializeCollectionToXml( PxOutputStream& outputStream, PxCollection& collection, PxSerializationRegistry& sr, PxCooking* cooking, const PxCollection* externalRefs, PxXmlMiscParameter* inArgs )
{
if( !PxSerialization::isSerializable(collection, sr, const_cast<PxCollection*>(externalRefs)) )
return false;
bool bRet = true;
SerializationRegistry& sn = static_cast<SerializationRegistry&>(sr);
PxRepXInstantiationArgs args( sn.getPhysics(), cooking );
PxCollection* tmpCollection = PxCreateCollection();
PX_ASSERT(tmpCollection);
tmpCollection->add( collection );
if(externalRefs)
{
tmpCollection->add(*const_cast<PxCollection*>(externalRefs));
}
PxAllocatorCallback& allocator = PxGetFoundation().getAllocatorCallback();
Sn::RepXCollection* theRepXCollection = Sn::create(sn, allocator, *tmpCollection );
if(inArgs != NULL)
{
theRepXCollection->setTolerancesScale(inArgs->scale);
theRepXCollection->setUpVector(inArgs->upVector);
}
PxU32 nbObjects = collection.getNbObjects();
if( nbObjects )
{
sortCollection( static_cast<Cm::Collection&>(collection), sn, true);
for( PxU32 i = 0; i < nbObjects; i++ )
{
PxBase& s = collection.getObject(i);
if( PxConcreteType::eSHAPE == s.getConcreteType() )
{
PxShape& shape = static_cast<PxShape&>(s);
if( shape.isExclusive() )
continue;
}
PxSerialObjectId id = collection.getId(s);
if(id == PX_SERIAL_OBJECT_ID_INVALID)
id = static_cast<PxSerialObjectId>( reinterpret_cast<size_t>( &s ));
PxRepXObject ro = PxCreateRepXObject( &s, id );
if ( ro.serializable == NULL || ro.id == 0 )
{
bRet = false;
break;
}
theRepXCollection->addRepXObjectToCollection( ro, tmpCollection, args );
}
}
tmpCollection->release();
theRepXCollection->save(outputStream);
theRepXCollection->destroy();
return bRet;
}
PxCollection* PxSerialization::createCollectionFromXml(PxInputData& inputData, PxCooking& cooking, PxSerializationRegistry& sr, const PxCollection* externalRefs, PxStringTable* stringTable, PxXmlMiscParameter* outArgs)
{
SerializationRegistry& sn = static_cast<SerializationRegistry&>(sr);
PxCollection* collection = PxCreateCollection();
PX_ASSERT(collection);
if( externalRefs )
collection->add(*const_cast<PxCollection*>(externalRefs));
PxAllocatorCallback& allocator = PxGetFoundation().getAllocatorCallback();
Sn::RepXCollection* theRepXCollection = Sn::create(sn, inputData, allocator, *collection);
theRepXCollection = &Sn::RepXUpgrader::upgradeCollection( *theRepXCollection );
PxRepXInstantiationArgs args( sn.getPhysics(), &cooking, stringTable );
if( !theRepXCollection->instantiateCollection(args, *collection) )
{
collection->release();
theRepXCollection->destroy();
return NULL;
}
if( externalRefs )
collection->remove(*const_cast<PxCollection*>(externalRefs));
if(outArgs != NULL)
{
outArgs->upVector = theRepXCollection->getUpVector();
outArgs->scale = theRepXCollection->getTolerancesScale();
}
theRepXCollection->destroy();
return collection;
}
}

View File

@ -0,0 +1,117 @@
//
// 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-2021 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_XML_SERIALIZER_H
#define PX_XML_SERIALIZER_H
#include "PxExtensionMetaDataObjects.h"
#include "SnXmlVisitorWriter.h"
namespace physx {
namespace Sn {
void writeHeightFieldSample( PxOutputStream& inStream, const PxHeightFieldSample& inSample )
{
PxU32 retval = 0;
PxU8* writePtr( reinterpret_cast< PxU8*>( &retval ) );
const PxU8* inPtr( reinterpret_cast<const PxU8*>( &inSample ) );
if ( isBigEndian() )
{
//Height field samples are a
//16 bit integer followed by two bytes.
//right now, data is 2 1 3 4
//We need a 32 bit integer that
//when read in by a LE system is 4 3 2 1.
//Thus, we need a BE integer that looks like:
//4 3 2 1
writePtr[0] = inPtr[3];
writePtr[1] = inPtr[2];
writePtr[2] = inPtr[0];
writePtr[3] = inPtr[1];
}
else
{
writePtr[0] = inPtr[0];
writePtr[1] = inPtr[1];
writePtr[2] = inPtr[2];
writePtr[3] = inPtr[3];
}
inStream << retval;
}
template<typename TDataType, typename TWriteOperator>
inline void writeStridedBufferProperty( XmlWriter& writer, MemoryBuffer& tempBuffer, const char* inPropName, const void* inData, PxU32 inStride, PxU32 inCount, PxU32 inItemsPerLine, TWriteOperator inOperator )
{
PX_ASSERT( inStride == 0 || inStride == sizeof( TDataType ) );
PX_UNUSED( inStride );
writeBuffer( writer, tempBuffer
, inItemsPerLine, reinterpret_cast<const TDataType*>( inData )
, inCount, inPropName, inOperator );
}
template<typename TDataType, typename TWriteOperator>
inline void writeStridedBufferProperty( XmlWriter& writer, MemoryBuffer& tempBuffer, const char* inPropName, const PxStridedData& inData, PxU32 inCount, PxU32 inItemsPerLine, TWriteOperator inOperator )
{
writeStridedBufferProperty<TDataType>( writer, tempBuffer, inPropName, inData.data, inData.stride, inCount, inItemsPerLine, inOperator );
}
template<typename TDataType, typename TWriteOperator>
inline void writeStridedBufferProperty( XmlWriter& writer, MemoryBuffer& tempBuffer, const char* inPropName, const PxTypedStridedData<TDataType>& inData, PxU32 inCount, PxU32 inItemsPerLine, TWriteOperator inOperator )
{
writeStridedBufferProperty<TDataType>( writer, tempBuffer, inPropName, inData.data, inData.stride, inCount, inItemsPerLine, inOperator );
}
template<typename TDataType, typename TWriteOperator>
inline void writeStridedBufferProperty( XmlWriter& writer, MemoryBuffer& tempBuffer, const char* inPropName, const PxBoundedData& inData, PxU32 inItemsPerLine, TWriteOperator inWriteOperator )
{
writeStridedBufferProperty<TDataType>( writer, tempBuffer, inPropName, inData, inData.count, inItemsPerLine, inWriteOperator );
}
template<typename TDataType, typename TWriteOperator>
inline void writeStridedBufferProperty( XmlWriter& writer, MemoryBuffer& tempBuffer, const char* inPropName, PxStrideIterator<const TDataType>& inData, PxU32 inCount, PxU32 inItemsPerLine, TWriteOperator inWriteOperator )
{
writeStrideBuffer<TDataType>(writer, tempBuffer
, inItemsPerLine, inData, PtrAccess<TDataType>
, inCount, inPropName, inData.stride(), inWriteOperator );
}
template<typename TDataType>
inline void writeStridedFlagsProperty( XmlWriter& writer, MemoryBuffer& tempBuffer, const char* inPropName, PxStrideIterator<const TDataType>& inData, PxU32 inCount, PxU32 inItemsPerLine, const PxU32ToName* inTable )
{
writeStrideFlags<TDataType>(writer, tempBuffer
, inItemsPerLine, inData, PtrAccess<TDataType>
, inCount, inPropName, inTable );
}
}
}
#endif

View File

@ -0,0 +1,215 @@
//
// 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-2021 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_SIMPLEXMLWRITER_H
#define PX_SIMPLEXMLWRITER_H
#include "PsArray.h"
#include "SnXmlMemoryPoolStreams.h"
#include "CmPhysXCommon.h"
namespace physx { namespace Sn {
class XmlWriter
{
public:
struct STagWatcher
{
typedef XmlWriter TXmlWriterType;
TXmlWriterType& mWriter;
STagWatcher( const STagWatcher& inOther );
STagWatcher& operator-( const STagWatcher& inOther );
STagWatcher( TXmlWriterType& inWriter, const char* inTagName )
: mWriter( inWriter )
{
mWriter.beginTag( inTagName );
}
~STagWatcher() { mWriter.endTag(); }
};
virtual ~XmlWriter(){}
virtual void beginTag( const char* inTagname ) = 0;
virtual void endTag() = 0;
virtual void addAttribute( const char* inName, const char* inValue ) = 0;
virtual void writeContentTag( const char* inTag, const char* inContent ) = 0;
virtual void addContent( const char* inContent ) = 0;
virtual PxU32 tabCount() = 0;
};
template<typename TStreamType>
class XmlWriterImpl : public XmlWriter
{
PxProfileAllocatorWrapper mWrapper;
TStreamType& mStream;
XmlWriterImpl( const XmlWriterImpl& inOther );
XmlWriterImpl& operator=( const XmlWriterImpl& inOther );
PxProfileArray<const char*> mTags;
bool mTagOpen;
PxU32 mInitialTagDepth;
public:
XmlWriterImpl( TStreamType& inStream, PxAllocatorCallback& inAllocator, PxU32 inInitialTagDepth = 0 )
: mWrapper( inAllocator )
, mStream( inStream )
, mTags( mWrapper )
, mTagOpen( false )
, mInitialTagDepth( inInitialTagDepth )
{
}
virtual ~XmlWriterImpl()
{
while( mTags.size() )
endTag();
}
PxU32 tabCount() { return mTags.size() + mInitialTagDepth; }
void writeTabs( PxU32 inSize )
{
inSize += mInitialTagDepth;
for ( PxU32 idx =0; idx < inSize; ++idx )
mStream << "\t";
}
void beginTag( const char* inTagname )
{
closeTag();
writeTabs(mTags.size());
mTags.pushBack( inTagname );
mStream << "<" << inTagname;
mTagOpen = true;
}
void addAttribute( const char* inName, const char* inValue )
{
PX_ASSERT( mTagOpen );
mStream << " " << inName << "=" << "\"" << inValue << "\"";
}
void closeTag(bool useNewline = true)
{
if ( mTagOpen )
{
mStream << " " << ">";
if (useNewline )
mStream << "\n";
}
mTagOpen = false;
}
void doEndOpenTag()
{
mStream << "</" << mTags.back() << ">" << "\n";
}
void endTag()
{
PX_ASSERT( mTags.size() );
if ( mTagOpen )
mStream << " " << "/>" << "\n";
else
{
writeTabs(mTags.size()-1);
doEndOpenTag();
}
mTagOpen = false;
mTags.popBack();
}
void addContent( const char* inContent )
{
closeTag(false);
mStream << inContent;
}
void writeContentTag( const char* inTag, const char* inContent )
{
beginTag( inTag );
addContent( inContent );
doEndOpenTag();
mTags.popBack();
}
void insertXml( const char* inXml )
{
closeTag();
mStream << inXml;
}
};
struct BeginTag
{
const char* mTagName;
BeginTag( const char* inTagName )
: mTagName( inTagName ) { }
};
struct EndTag
{
EndTag() {}
};
struct Att
{
const char* mAttName;
const char* mAttValue;
Att( const char* inAttName, const char* inAttValue )
: mAttName( inAttName )
, mAttValue( inAttValue ) { }
};
struct Content
{
const char* mContent;
Content( const char* inContent )
: mContent( inContent ) { }
};
struct ContentTag
{
const char* mTagName;
const char* mContent;
ContentTag( const char* inTagName, const char* inContent )
: mTagName( inTagName )
, mContent( inContent ) { }
};
inline XmlWriter& operator<<( XmlWriter& inWriter, const BeginTag& inTag ) { inWriter.beginTag( inTag.mTagName ); return inWriter; }
inline XmlWriter& operator<<( XmlWriter& inWriter, const EndTag& inTag ) { inWriter.endTag(); return inWriter; }
inline XmlWriter& operator<<( XmlWriter& inWriter, const Att& inTag ) { inWriter.addAttribute(inTag.mAttName, inTag.mAttValue); return inWriter; }
inline XmlWriter& operator<<( XmlWriter& inWriter, const Content& inTag ) { inWriter.addContent(inTag.mContent); return inWriter; }
inline XmlWriter& operator<<( XmlWriter& inWriter, const ContentTag& inTag ) { inWriter.writeContentTag(inTag.mTagName, inTag.mContent); return inWriter; }
inline void writeProperty( XmlWriter& inWriter, MemoryBuffer& tempBuffer, const char* inPropName )
{
PxU8 data = 0;
tempBuffer.write( &data, sizeof(PxU8) );
inWriter.writeContentTag( inPropName, reinterpret_cast<const char*>( tempBuffer.mBuffer ) );
tempBuffer.clear();
}
template<typename TDataType>
inline void writeProperty( XmlWriter& inWriter, MemoryBuffer& tempBuffer, const char* inPropName, TDataType inValue )
{
tempBuffer << inValue;
writeProperty( inWriter, tempBuffer, inPropName );
}
} }
#endif

View File

@ -0,0 +1,277 @@
//
// 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-2021 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_XML_STRINGTOTYPE_H
#define PX_XML_STRINGTOTYPE_H
#include "common/PxCoreUtilityTypes.h"
#include "PxFiltering.h"
#include "PsString.h"
#include <stdio.h>
#include <ctype.h>
//Remapping function name for gcc-based systems.
#ifndef _MSC_VER
#define _strtoui64 strtoull
#endif
namespace physx { namespace Sn {
template<typename TDataType>
struct StrToImpl
{
bool compile_error;
};
template<> struct StrToImpl<PxU64> {
//Id's (void ptrs) are written to file as unsigned
//64 bit integers, so this method gets called more
//often than one might think.
PX_INLINE void strto( PxU64& ioDatatype,const char*& ioData )
{
ioDatatype = _strtoui64( ioData, const_cast<char **>(&ioData), 10 );
}
};
PX_INLINE PxF32 strToFloat(const char *str,const char **nextScan)
{
PxF32 ret;
while ( *str && isspace(static_cast<unsigned char>(*str))) str++; // skip leading whitespace
char temp[256] = "";
char *dest = temp;
char *end = &temp[255];
const char *begin = str;
while ( *str && !isspace(static_cast<unsigned char>(*str)) && dest < end ) // copy the number up to the first whitespace or eos
{
*dest++ = *str++;
}
*dest = 0;
ret = PxF32(strtod(temp,&end));
if ( nextScan )
{
*nextScan = begin+(end-temp);
}
return ret;
}
template<> struct StrToImpl<PxU32> {
PX_INLINE void strto( PxU32& ioDatatype,const char*& ioData )
{
ioDatatype = static_cast<PxU32>( strtoul( ioData,const_cast<char **>(&ioData), 10 ) );
}
};
template<> struct StrToImpl<PxI32> {
PX_INLINE void strto( PxI32& ioDatatype,const char*& ioData )
{
ioDatatype = static_cast<PxI32>( strtoul( ioData,const_cast<char **>(&ioData), 10 ) );
}
};
template<> struct StrToImpl<PxU16> {
PX_INLINE void strto( PxU16& ioDatatype,const char*& ioData )
{
ioDatatype = static_cast<PxU16>( strtoul( ioData,const_cast<char **>(&ioData), 10 ) );
}
};
PX_INLINE void eatwhite(const char*& ioData )
{
if ( ioData )
{
while( isspace( static_cast<unsigned char>(*ioData) ) )
++ioData;
}
}
// copy the source data to the dest buffer until the first whitespace is encountered.
// Do not overflow the buffer based on the bufferLen provided.
// Advance the input 'ioData' pointer so that it sits just at the next whitespace
PX_INLINE void nullTerminateWhite(const char*& ioData,char *buffer,PxU32 bufferLen)
{
if ( ioData )
{
char *eof = buffer+(bufferLen-1);
char *dest = buffer;
while( *ioData && !isspace(static_cast<unsigned char>(*ioData)) && dest < eof )
{
*dest++ = *ioData++;
}
*dest = 0;
}
}
inline void nonNullTerminateWhite(const char*& ioData )
{
if ( ioData )
{
while( *ioData && !isspace( static_cast<unsigned char>(*ioData) ) )
++ioData;
}
}
template<> struct StrToImpl<PxF32> {
inline void strto( PxF32& ioDatatype,const char*& ioData )
{
ioDatatype = strToFloat(ioData,&ioData);
}
};
template<> struct StrToImpl<void*> {
inline void strto( void*& ioDatatype,const char*& ioData )
{
PxU64 theData;
StrToImpl<PxU64>().strto( theData, ioData );
ioDatatype = reinterpret_cast<void*>( static_cast<size_t>( theData ) );
}
};
template<> struct StrToImpl<physx::PxVec3> {
inline void strto( physx::PxVec3& ioDatatype,const char*& ioData )
{
StrToImpl<PxF32>().strto( ioDatatype[0], ioData );
StrToImpl<PxF32>().strto( ioDatatype[1], ioData );
StrToImpl<PxF32>().strto( ioDatatype[2], ioData );
}
};
template<> struct StrToImpl<PxU8*> {
inline void strto( PxU8*& /*ioDatatype*/,const char*& /*ioData*/)
{
}
};
template<> struct StrToImpl<bool> {
inline void strto( bool& ioType,const char*& inValue )
{
ioType = physx::shdfnd::stricmp( inValue, "true" ) == 0 ? true : false;
}
};
template<> struct StrToImpl<PxU8> {
PX_INLINE void strto( PxU8& ioType,const char* & inValue)
{
ioType = static_cast<PxU8>( strtoul( inValue,const_cast<char **>(&inValue), 10 ) );
}
};
template<> struct StrToImpl<PxFilterData> {
PX_INLINE void strto( PxFilterData& ioType,const char*& inValue)
{
ioType.word0 = static_cast<PxU32>( strtoul( inValue,const_cast<char **>(&inValue), 10 ) );
ioType.word1 = static_cast<PxU32>( strtoul( inValue,const_cast<char **>(&inValue), 10 ) );
ioType.word2 = static_cast<PxU32>( strtoul( inValue,const_cast<char **>(&inValue), 10 ) );
ioType.word3 = static_cast<PxU32>( strtoul( inValue, NULL, 10 ) );
}
};
template<> struct StrToImpl<PxQuat> {
PX_INLINE void strto( PxQuat& ioType,const char*& inValue )
{
ioType.x = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.y = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.z = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.w = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
}
};
template<> struct StrToImpl<PxTransform> {
PX_INLINE void strto( PxTransform& ioType,const char*& inValue)
{
ioType.q.x = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.q.y = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.q.z = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.q.w = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.p[0] = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.p[1] = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.p[2] = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
}
};
template<> struct StrToImpl<PxBounds3> {
PX_INLINE void strto( PxBounds3& ioType,const char*& inValue)
{
ioType.minimum[0] = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.minimum[1] = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.minimum[2] = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.maximum[0] = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.maximum[1] = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.maximum[2] = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
}
};
template<> struct StrToImpl<PxMetaDataPlane> {
PX_INLINE void strto( PxMetaDataPlane& ioType,const char*& inValue)
{
ioType.normal.x = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.normal.y = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.normal.z = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
ioType.distance = static_cast<PxReal>( strToFloat( inValue, &inValue ) );
}
};
template<> struct StrToImpl<PxRigidDynamic*> {
PX_INLINE void strto( PxRigidDynamic*& /*ioDatatype*/,const char*& /*ioData*/)
{
}
};
template<typename TDataType>
inline void strto( TDataType& ioType,const char*& ioData )
{
if ( ioData && *ioData ) StrToImpl<TDataType>().strto( ioType, ioData );
}
template<typename TDataType>
inline void strtoLong( TDataType& ioType,const char*& ioData )
{
if ( ioData && *ioData ) StrToImpl<TDataType>().strto( ioType, ioData );
}
template<typename TDataType>
inline void stringToType( const char* inValue, TDataType& ioType )
{
const char* theValue( inValue );
return strto( ioType, theValue );
}
} }
#endif

View File

@ -0,0 +1,931 @@
//
// 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-2021 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_XML_VISITOR_READER_H
#define PX_XML_VISITOR_READER_H
#include "PsArray.h"
#include "PsUtilities.h"
#include "RepXMetaDataPropertyVisitor.h"
#include "SnPxStreamOperators.h"
#include "SnXmlMemoryPoolStreams.h"
#include "SnXmlReader.h"
#include "SnXmlImpl.h"
#include "SnXmlMemoryAllocator.h"
#include "SnXmlStringToType.h"
namespace physx { namespace Sn {
inline PxU32 findEnumByName( const char* inName, const PxU32ToName* inTable )
{
for ( PxU32 idx = 0; inTable[idx].mName != NULL; ++idx )
{
if ( physx::shdfnd::stricmp( inTable[idx].mName, inName ) == 0 )
return inTable[idx].mValue;
}
return 0;
}
PX_INLINE void stringToFlagsType( const char* strData, XmlMemoryAllocator& alloc, PxU32& ioType, const PxU32ToName* inTable )
{
if ( inTable == NULL )
return;
ioType = 0;
if ( strData && *strData)
{
//Destructively parse the string to get out the different flags.
char* theValue = const_cast<char*>( copyStr( &alloc, strData ) );
char* theMarker = theValue;
char* theNext = theValue;
while( theNext && *theNext )
{
++theNext;
if( *theNext == '|' )
{
*theNext = 0;
++theNext;
ioType |= static_cast< PxU32 > ( findEnumByName( theMarker, inTable ) );
theMarker = theNext;
}
}
if ( theMarker && *theMarker )
ioType |= static_cast< PxU32 > ( findEnumByName( theMarker, inTable ) );
alloc.deallocate( reinterpret_cast<PxU8*>( theValue ) );
}
}
template<typename TDataType>
PX_INLINE void stringToEnumType( const char* strData, TDataType& ioType, const PxU32ToName* inTable )
{
ioType = static_cast<TDataType>( findEnumByName( strData, inTable ) );
}
template<typename TDataType>
PX_INLINE bool readProperty( XmlReader& inReader, const char* pname, TDataType& ioType )
{
const char* value;
if ( inReader.read( pname, value ) )
{
stringToType( value, ioType );
return true;
}
return false;
}
template<typename TObjType>
inline TObjType* findReferencedObject( PxCollection& collection, PxSerialObjectId id)
{
PX_ASSERT(id > 0);
TObjType* outObject = static_cast<TObjType*>(const_cast<PxBase*>(collection.find(id)));
if (outObject == NULL)
{
Ps::getFoundation().error(PxErrorCode::eINVALID_PARAMETER, __FILE__, __LINE__,
"PxSerialization::createCollectionFromXml: "
"Reference to ID %d cannot be resolved. Make sure externalRefs collection is specified if required and "
"check Xml file for completeness.",
id);
}
return outObject;
}
template<typename TObjType>
inline bool readReference( XmlReader& inReader, PxCollection& collection, TObjType*& outObject )
{
PxSerialObjectId theId;
const char* theValue = inReader.getCurrentItemValue();
strto( theId, theValue );
if( theId == 0)
{
// the NULL pointer is a valid pointer if the input id is 0
outObject = NULL;
return true;
}
else
{
outObject = findReferencedObject<TObjType>(collection, theId);
return outObject != NULL;
}
}
template<typename TObjType>
inline bool readReference( XmlReader& inReader, PxCollection& inCollection, const char* pname, TObjType*& outObject )
{
outObject = NULL;
PxSerialObjectId theId = 0;
if (readProperty ( inReader, pname, theId ) && theId )
{
outObject = findReferencedObject<TObjType>(inCollection, theId);
}
// the NULL pointer is a valid pointer if the input id is 0
return (outObject != NULL) || 0 == theId;
}
template<typename TEnumType, typename TStorageType>
inline bool readFlagsProperty( XmlReader& reader, XmlMemoryAllocator& allocator, const char* pname, const PxU32ToName* inConversions, PxFlags<TEnumType,TStorageType>& outFlags )
{
const char* value;
if ( reader.read( pname, value ) )
{
PxU32 tempValue = 0;
stringToFlagsType( value, allocator, tempValue, inConversions );
outFlags = PxFlags<TEnumType,TStorageType>(Ps::to16(tempValue) );
return true;
}
return false;
}
template<typename TObjType, typename TReaderType, typename TInfoType>
inline void readComplexObj( TReaderType& oldVisitor, TObjType* inObj, TInfoType& info);
template<typename TObjType, typename TReaderType>
inline void readComplexObj( TReaderType& oldVisitor, TObjType* inObj);
template<typename TReaderType, typename TGeomType>
inline PxGeometry* parseGeometry( TReaderType& reader, TGeomType& /*inGeom*/)
{
PxAllocatorCallback& inAllocator = reader.mAllocator.getAllocator();
TGeomType* shape = PX_PLACEMENT_NEW((inAllocator.allocate(sizeof(TGeomType), "parseGeometry", __FILE__, __LINE__ )), TGeomType);
PxClassInfoTraits<TGeomType> info;
readComplexObj( reader, shape);
return shape;
}
template<typename TReaderType>
inline void parseShape( TReaderType& visitor, PxGeometry*& outResult, Ps::Array<PxMaterial*>& outMaterials)
{
XmlReader& theReader( visitor.mReader );
PxCollection& collection = visitor.mCollection;
visitor.pushCurrentContext();
if ( visitor.gotoTopName() )
{
visitor.pushCurrentContext();
if ( visitor.gotoChild( "Materials" ) )
{
for( bool matSuccess = visitor.gotoFirstChild(); matSuccess;
matSuccess = visitor.gotoNextSibling() )
{
PxMaterial* material = NULL;
if(!readReference<PxMaterial>( theReader, collection, material ))
visitor.mHadError = true;
if ( material )
outMaterials.pushBack( material );
}
}
visitor.popCurrentContext();
visitor.pushCurrentContext();
PxPlaneGeometry plane;
PxHeightFieldGeometry heightField;
PxSphereGeometry sphere;
PxTriangleMeshGeometry mesh;
PxConvexMeshGeometry convex;
PxBoxGeometry box;
PxCapsuleGeometry capsule;
if ( visitor.gotoChild( "Geometry" ) )
{
if ( visitor.gotoFirstChild() )
{
const char* geomTypeName = visitor.getCurrentItemName();
if ( physx::shdfnd::stricmp( geomTypeName, "PxSphereGeometry" ) == 0 ) outResult = parseGeometry(visitor, sphere);
else if ( physx::shdfnd::stricmp( geomTypeName, "PxPlaneGeometry" ) == 0 ) outResult = parseGeometry(visitor, plane);
else if ( physx::shdfnd::stricmp( geomTypeName, "PxCapsuleGeometry" ) == 0 ) outResult = parseGeometry(visitor, capsule);
else if ( physx::shdfnd::stricmp( geomTypeName, "PxBoxGeometry" ) == 0 ) outResult = parseGeometry(visitor, box);
else if ( physx::shdfnd::stricmp( geomTypeName, "PxConvexMeshGeometry" ) == 0 ) outResult = parseGeometry(visitor, convex);
else if ( physx::shdfnd::stricmp( geomTypeName, "PxTriangleMeshGeometry" ) == 0 ) outResult = parseGeometry(visitor, mesh);
else if ( physx::shdfnd::stricmp( geomTypeName, "PxHeightFieldGeometry" ) == 0 ) outResult = parseGeometry(visitor, heightField);
else
PX_ASSERT( false );
}
}
visitor.popCurrentContext();
}
visitor.popCurrentContext();
return;
}
template<typename TReaderType, typename TObjType>
inline void readShapesProperty( TReaderType& visitor, TObjType* inObj, const PxRigidActorShapeCollection* inProp = NULL, bool isSharedShape = false )
{
PX_UNUSED(isSharedShape);
PX_UNUSED(inProp);
XmlReader& theReader( visitor.mReader );
PxCollection& collection( visitor.mCollection );
visitor.pushCurrentContext();
if ( visitor.gotoTopName() )
{
//uggh working around the shape collection api.
//read out materials and geometry
for ( bool success = visitor.gotoFirstChild(); success;
success = visitor.gotoNextSibling() )
{
if( 0 == physx::shdfnd::stricmp( visitor.getCurrentItemName(), "PxShapeRef" ) )
{
PxShape* shape = NULL;
if(!readReference<PxShape>( theReader, collection, shape ))
visitor.mHadError = true;
if(shape)
inObj->attachShape( *shape );
}
else
{
Ps::Array<PxMaterial*> materials;
PxGeometry* geometry = NULL;
parseShape( visitor, geometry, materials);
PxShape* theShape = NULL;
if ( materials.size() )
{
theShape = visitor.mArgs.physics.createShape( *geometry, materials.begin(), Ps::to16(materials.size()), true );
if ( theShape )
{
readComplexObj( visitor, theShape );
if(theShape)
{
inObj->attachShape(*theShape);
collection.add( *theShape );
}
}
}
switch(geometry->getType())
{
case PxGeometryType::eSPHERE :
static_cast<PxSphereGeometry*>(geometry)->~PxSphereGeometry();
break;
case PxGeometryType::ePLANE :
static_cast<PxPlaneGeometry*>(geometry)->~PxPlaneGeometry();
break;
case PxGeometryType::eCAPSULE :
static_cast<PxCapsuleGeometry*>(geometry)->~PxCapsuleGeometry();
break;
case PxGeometryType::eBOX :
static_cast<PxBoxGeometry*>(geometry)->~PxBoxGeometry();
break;
case PxGeometryType::eCONVEXMESH :
static_cast<PxConvexMeshGeometry*>(geometry)->~PxConvexMeshGeometry();
break;
case PxGeometryType::eTRIANGLEMESH :
static_cast<PxTriangleMeshGeometry*>(geometry)->~PxTriangleMeshGeometry();
break;
case PxGeometryType::eHEIGHTFIELD :
static_cast<PxHeightFieldGeometry*>(geometry)->~PxHeightFieldGeometry();
break;
case PxGeometryType::eGEOMETRY_COUNT:
case PxGeometryType::eINVALID:
PX_ASSERT(0);
}
visitor.mAllocator.getAllocator().deallocate(geometry);
}
}
}
visitor.popCurrentContext();
}
struct ReaderNameStackEntry : NameStackEntry
{
bool mValid;
ReaderNameStackEntry( const char* nm, bool valid ) : NameStackEntry(nm), mValid(valid) {}
};
typedef PxProfileArray<ReaderNameStackEntry> TReaderNameStack;
template<typename TObjType>
struct RepXVisitorReaderBase
{
protected:
RepXVisitorReaderBase<TObjType>& operator=(const RepXVisitorReaderBase<TObjType>&);
public:
TReaderNameStack& mNames;
PxProfileArray<PxU32>& mContexts;
PxRepXInstantiationArgs mArgs;
XmlReader& mReader;
TObjType* mObj;
XmlMemoryAllocator& mAllocator;
PxCollection& mCollection;
bool mValid;
bool& mHadError;
RepXVisitorReaderBase( TReaderNameStack& names, PxProfileArray<PxU32>& contexts, const PxRepXInstantiationArgs& args, XmlReader& reader, TObjType* obj
, XmlMemoryAllocator& alloc, PxCollection& collection, bool& hadError )
: mNames( names )
, mContexts( contexts )
, mArgs( args )
, mReader( reader )
, mObj( obj )
, mAllocator( alloc )
, mCollection( collection )
, mValid( true )
, mHadError(hadError)
{
}
RepXVisitorReaderBase( const RepXVisitorReaderBase& other )
: mNames( other.mNames )
, mContexts( other.mContexts )
, mArgs( other.mArgs )
, mReader( other.mReader )
, mObj( other.mObj )
, mAllocator( other.mAllocator )
, mCollection( other.mCollection )
, mValid( other.mValid )
, mHadError( other.mHadError )
{
}
void pushName( const char* name )
{
gotoTopName();
mNames.pushBack( ReaderNameStackEntry( name, mValid ) );
}
void pushBracketedName( const char* name ) { pushName( name ); }
void popName()
{
if ( mNames.size() )
{
if ( mNames.back().mOpen && mNames.back().mValid )
mReader.leaveChild();
mNames.popBack();
}
mValid =true;
if ( mNames.size() && mNames.back().mValid == false )
mValid = false;
}
void pushCurrentContext()
{
mContexts.pushBack( static_cast<PxU32>( mNames.size() ) );
}
void popCurrentContext()
{
if ( mContexts.size() )
{
PxU32 depth = mContexts.back();
PX_ASSERT( mNames.size() >= depth );
while( mNames.size() > depth )
popName();
mContexts.popBack();
}
}
bool updateLastEntryAfterOpen()
{
mNames.back().mValid = mValid;
mNames.back().mOpen = mValid;
return mValid;
}
bool gotoTopName()
{
if ( mNames.size() && mNames.back().mOpen == false )
{
if ( mValid )
mValid = mReader.gotoChild( mNames.back().mName );
updateLastEntryAfterOpen();
}
return mValid;
}
bool isValid() const { return mValid; }
bool gotoChild( const char* name )
{
pushName( name );
return gotoTopName();
}
bool gotoFirstChild()
{
pushName( "__child" );
if ( mValid ) mValid = mReader.gotoFirstChild();
return updateLastEntryAfterOpen();
}
bool gotoNextSibling()
{
bool retval = mValid;
if ( mValid ) retval = mReader.gotoNextSibling();
return retval;
}
const char* getCurrentItemName() { if (mValid ) return mReader.getCurrentItemName(); return ""; }
const char* topName() const
{
if ( mNames.size() ) return mNames.back().mName;
PX_ASSERT( false );
return "bad__repx__name";
}
const char* getCurrentValue()
{
const char* value = NULL;
if ( isValid() && mReader.read( topName(), value ) )
return value;
return NULL;
}
template<typename TDataType>
bool readProperty(TDataType& outType)
{
const char* value = getCurrentValue();
if ( value && *value )
{
stringToType( value, outType );
return true;
}
return false;
}
template<typename TDataType>
bool readExtendedIndexProperty(TDataType& outType)
{
const char* value = mReader.getCurrentItemValue();
if ( value && *value )
{
stringToType( value, outType );
return true;
}
return false;
}
template<typename TRefType>
bool readReference(TRefType*& outRef)
{
return physx::Sn::readReference<TRefType>( mReader, mCollection, topName(), outRef );
}
inline bool readProperty(const char*& outProp )
{
outProp = "";
const char* value = getCurrentValue();
if ( value && *value && mArgs.stringTable )
{
outProp = mArgs.stringTable->allocateStr( value );
return true;
}
return false;
}
inline bool readProperty(PxConvexMesh*& outProp )
{
return readReference<PxConvexMesh>( outProp );
}
inline bool readProperty(PxTriangleMesh*& outProp )
{
return readReference<PxTriangleMesh>( outProp );
}
inline bool readProperty(PxBVH33TriangleMesh*& outProp )
{
return readReference<PxBVH33TriangleMesh>( outProp );
}
inline bool readProperty(PxBVH34TriangleMesh*& outProp )
{
return readReference<PxBVH34TriangleMesh>( outProp );
}
inline bool readProperty(PxHeightField*& outProp )
{
return readReference<PxHeightField>( outProp );
}
inline bool readProperty( PxRigidActor *& outProp )
{
return readReference<PxRigidActor>( outProp );
}
template<typename TAccessorType>
void simpleProperty( PxU32 /*key*/, TAccessorType& inProp )
{
typedef typename TAccessorType::prop_type TPropertyType;
TPropertyType value;
if ( readProperty( value ) )
inProp.set( mObj, value );
}
template<typename TAccessorType>
void enumProperty( PxU32 /*key*/, TAccessorType& inProp, const PxU32ToName* inConversions )
{
typedef typename TAccessorType::prop_type TPropertyType;
const char* strVal = getCurrentValue();
if ( strVal && *strVal )
{
TPropertyType pval;
stringToEnumType( strVal, pval, inConversions );
inProp.set( mObj, pval );
}
}
template<typename TAccessorType>
void flagsProperty( PxU32 /*key*/, const TAccessorType& inProp, const PxU32ToName* inConversions )
{
typedef typename TAccessorType::prop_type TPropertyType;
typedef typename TPropertyType::InternalType TInternalType;
const char* strVal = getCurrentValue();
if ( strVal && *strVal )
{
PxU32 tempValue = 0;
stringToFlagsType( strVal, mAllocator, tempValue, inConversions );
inProp.set( mObj, TPropertyType(TInternalType( tempValue )));
}
}
template<typename TAccessorType, typename TInfoType>
void complexProperty( PxU32* /*key*/, const TAccessorType& inProp, TInfoType& inInfo )
{
typedef typename TAccessorType::prop_type TPropertyType;
if ( gotoTopName() )
{
TPropertyType propVal = inProp.get( mObj );
readComplexObj( *this, &propVal, inInfo );
inProp.set( mObj, propVal );
}
}
template<typename TAccessorType, typename TInfoType>
void bufferCollectionProperty( PxU32* /*key*/, const TAccessorType& inProp, TInfoType& inInfo )
{
typedef typename TAccessorType::prop_type TPropertyType;
Ps::InlineArray<TPropertyType,5> theData;
this->pushCurrentContext();
if ( this->gotoTopName() )
{
for ( bool success = this->gotoFirstChild(); success;
success = this->gotoNextSibling() )
{
TPropertyType propVal;
readComplexObj( *this, &propVal, inInfo );
theData.pushBack(propVal);
}
}
this->popCurrentContext();
inProp.set( mObj, theData.begin(), theData.size() );
}
template<typename TAccessorType, typename TInfoType>
void extendedIndexedProperty( PxU32* /*key*/, const TAccessorType& inProp, TInfoType& inInfo )
{
typedef typename TAccessorType::prop_type TPropertyType;
this->pushCurrentContext();
if ( this->gotoTopName() )
{
PxU32 index = 0;
for ( bool success = this->gotoFirstChild(); success;
success = this->gotoNextSibling() )
{
TPropertyType propVal;
readComplexObj( *this, &propVal, inInfo );
inProp.set(mObj, index, propVal);
++index;
}
}
this->popCurrentContext();
}
template<typename TAccessorType, typename TInfoType>
void PxFixedSizeLookupTableProperty( PxU32* /*key*/, const TAccessorType& inProp, TInfoType& inInfo )
{
typedef typename TAccessorType::prop_type TPropertyType;
const_cast<TAccessorType&>(inProp).clear( mObj );
this->pushCurrentContext();
if ( this->gotoTopName() )
{
for ( bool success = this->gotoFirstChild(); success;
success = this->gotoNextSibling() )
{
TPropertyType propXVal;
readComplexObj( *this, &propXVal, inInfo );
if(this->gotoNextSibling())
{
TPropertyType propYVal;
readComplexObj( *this, &propYVal, inInfo );
const_cast<TAccessorType&>(inProp).addPair(mObj, propXVal, propYVal);
}
}
}
this->popCurrentContext();
}
void handleShapes( const PxRigidActorShapeCollection& inProp )
{
physx::Sn::readShapesProperty( *this, mObj, &inProp );
}
void handleRigidActorGlobalPose(const PxRigidActorGlobalPosePropertyInfo& inProp)
{
PxArticulationLink* link = mObj->template is<PxArticulationLink>();
bool isReducedCoordinateLink = (link != NULL) && link->getArticulation().getConcreteType() == PxConcreteType::eARTICULATION_REDUCED_COORDINATE;
if (!isReducedCoordinateLink)
{
PxRepXPropertyAccessor<PxPropertyInfoName::PxRigidActor_GlobalPose, PxRigidActor, const PxTransform &, PxTransform> theAccessor( inProp );
simpleProperty(PxPropertyInfoName::PxRigidActor_GlobalPose, theAccessor);
}
}
};
template<typename TObjType>
struct RepXVisitorReader : public RepXVisitorReaderBase<TObjType>
{
RepXVisitorReader( TReaderNameStack& names, PxProfileArray<PxU32>& contexts, const PxRepXInstantiationArgs& args, XmlReader& reader, TObjType* obj
, XmlMemoryAllocator& alloc, PxCollection& collection, bool& ret)
: RepXVisitorReaderBase<TObjType>( names, contexts, args, reader, obj, alloc, collection, ret)
{
}
RepXVisitorReader( const RepXVisitorReader<TObjType>& other )
: RepXVisitorReaderBase<TObjType>( other )
{
}
};
// Specialized template to load dynamic rigid, to determine the kinematic state first
template<>
struct RepXVisitorReader<PxRigidDynamic> : public RepXVisitorReaderBase<PxRigidDynamic>
{
RepXVisitorReader( TReaderNameStack& names, PxProfileArray<PxU32>& contexts, const PxRepXInstantiationArgs& args, XmlReader& reader, PxRigidDynamic* obj
, XmlMemoryAllocator& alloc, PxCollection& collection, bool& ret)
: RepXVisitorReaderBase<PxRigidDynamic>( names, contexts, args, reader, obj, alloc, collection, ret)
{
}
RepXVisitorReader( const RepXVisitorReader<PxRigidDynamic>& other )
: RepXVisitorReaderBase<PxRigidDynamic>( other )
{
}
void handleShapes( const PxRigidActorShapeCollection& inProp )
{
// Need to read the parental actor to check if actor is kinematic
// in that case we need to apply the kinematic flag before a shape is set
XmlReaderWriter* parentReader = static_cast<XmlReaderWriter*>(mReader.getParentReader());
if(mObj)
{
const char* value;
if (parentReader->read( "RigidBodyFlags", value ))
{
if(strstr(value, "eKINEMATIC"))
{
mObj->setRigidBodyFlag(PxRigidBodyFlag::eKINEMATIC, true);
}
}
}
physx::Sn::readShapesProperty( *this, mObj, &inProp );
parentReader->release();
}
template<typename TAccessorType>
void simpleProperty( PxU32 /*key*/, TAccessorType& inProp )
{
typedef typename TAccessorType::prop_type TPropertyType;
TPropertyType value;
if (readProperty(value))
{
// If the rigid body is kinematic, we cannot set the LinearVelocity or AngularVelocity
const bool kinematic = (mObj->getRigidBodyFlags() & PxRigidBodyFlag::eKINEMATIC);
if(kinematic && (inProp.mProperty.mKey == PxPropertyInfoName::PxRigidBody_LinearVelocity || inProp.mProperty.mKey == PxPropertyInfoName::PxRigidBody_AngularVelocity))
return;
inProp.set(mObj, value );
}
}
private:
RepXVisitorReader<PxRigidDynamic>& operator=(const RepXVisitorReader<PxRigidDynamic>&);
};
template<>
struct RepXVisitorReader<PxShape> : public RepXVisitorReaderBase<PxShape>
{
RepXVisitorReader( TReaderNameStack& names, PxProfileArray<PxU32>& contexts, const PxRepXInstantiationArgs& args, XmlReader& reader, PxShape* obj
, XmlMemoryAllocator& alloc, PxCollection& collection, bool& ret )
: RepXVisitorReaderBase<PxShape>( names, contexts, args, reader, obj, alloc, collection, ret )
{
}
RepXVisitorReader( const RepXVisitorReader<PxShape>& other )
: RepXVisitorReaderBase<PxShape>( other )
{
}
void handleShapeMaterials( const PxShapeMaterialsProperty& ) //these were handled during construction.
{
}
void handleGeometryProperty( const PxShapeGeometryProperty& )
{
}
private:
RepXVisitorReader<PxShape>& operator=(const RepXVisitorReader<PxShape>&);
};
template<>
struct RepXVisitorReader<PxArticulationLink> : public RepXVisitorReaderBase<PxArticulationLink>
{
RepXVisitorReader( TReaderNameStack& names, PxProfileArray<PxU32>& contexts, const PxRepXInstantiationArgs& args, XmlReader& reader, PxArticulationLink* obj
, XmlMemoryAllocator& alloc, PxCollection& collection, bool& ret )
: RepXVisitorReaderBase<PxArticulationLink>( names, contexts, args, reader, obj, alloc, collection, ret )
{
}
RepXVisitorReader( const RepXVisitorReader<PxArticulationLink>& other )
: RepXVisitorReaderBase<PxArticulationLink>( other )
{
}
void handleIncomingJoint( const TIncomingJointPropType& prop )
{
pushName( "Joint" );
if ( gotoTopName() )
{
PxArticulationBase& articulationBase = mObj->getArticulation();
if (articulationBase.getConcreteType() == PxConcreteType::eARTICULATION)
{
PxArticulationJoint* theJoint = static_cast<PxArticulationJoint*>((prop.get(mObj)));
readComplexObj(*this, theJoint);
//Add joint to PxCollection, since PxArticulation requires PxArticulationLink and joint.
mCollection.add(*theJoint);
}
else
{
PX_ASSERT(articulationBase.getConcreteType() == PxConcreteType::eARTICULATION_REDUCED_COORDINATE);
PxArticulationJointReducedCoordinate* theJoint = static_cast<PxArticulationJointReducedCoordinate*>((prop.get(mObj)));
readComplexObj(*this, theJoint);
//Add joint to PxCollection, since PxArticulation requires PxArticulationLink and joint.
mCollection.add(*theJoint);
}
}
popName();
}
private:
RepXVisitorReader<PxArticulationLink>& operator=(const RepXVisitorReader<PxArticulationLink>&);
};
template<typename ArticulationType>
inline void readProperty( RepXVisitorReaderBase<ArticulationType>& inSerializer, ArticulationType* inObj, const PxArticulationLinkCollectionProp&)
{
PxProfileAllocatorWrapper theWrapper( inSerializer.mAllocator.getAllocator() );
PxCollection& collection( inSerializer.mCollection );
TArticulationLinkLinkMap linkRemapMap( theWrapper );
inSerializer.pushCurrentContext();
if( inSerializer.gotoTopName() )
{
for ( bool links = inSerializer.gotoFirstChild();
links != false;
links = inSerializer.gotoNextSibling() )
{
//Need enough information to create the link...
PxSerialObjectId theParentPtr = 0;
const PxArticulationLink* theParentLink = NULL;
if ( inSerializer.mReader.read( "Parent", theParentPtr ) )
{
const TArticulationLinkLinkMap::Entry* theRemappedParent( linkRemapMap.find( theParentPtr ) );
//If we have a valid at write time, we had better have a valid parent at read time.
PX_ASSERT( theRemappedParent );
theParentLink = theRemappedParent->second;
}
PxArticulationLink* newLink = inObj->createLink( const_cast<PxArticulationLink*>( theParentLink ), PxTransform(PxIdentity) );
PxSerialObjectId theIdPtr = 0;
inSerializer.mReader.read( "Id", theIdPtr );
linkRemapMap.insert( theIdPtr, newLink );
readComplexObj( inSerializer, newLink );
//Add link to PxCollection, since PxArticulation requires PxArticulationLink and joint.
collection.add( *newLink, theIdPtr );
}
}
inSerializer.popCurrentContext();
}
template<>
struct RepXVisitorReader<PxArticulation> : public RepXVisitorReaderBase<PxArticulation>
{
RepXVisitorReader( TReaderNameStack& names, PxProfileArray<PxU32>& contexts, const PxRepXInstantiationArgs& args, XmlReader& reader, PxArticulation* obj
, XmlMemoryAllocator& alloc, PxCollection& collection, bool& ret)
: RepXVisitorReaderBase<PxArticulation>( names, contexts, args, reader, obj, alloc, collection, ret)
{
}
RepXVisitorReader( const RepXVisitorReader<PxArticulation>& other )
: RepXVisitorReaderBase<PxArticulation>( other )
{
}
void handleArticulationLinks( const PxArticulationLinkCollectionProp& inProp )
{
physx::Sn::readProperty( *this, mObj, inProp );
}
};
template<>
struct RepXVisitorReader<PxArticulationReducedCoordinate> : public RepXVisitorReaderBase<PxArticulationReducedCoordinate>
{
RepXVisitorReader(TReaderNameStack& names, PxProfileArray<PxU32>& contexts, const PxRepXInstantiationArgs& args, XmlReader& reader, PxArticulationReducedCoordinate* obj
, XmlMemoryAllocator& alloc, PxCollection& collection, bool& ret)
: RepXVisitorReaderBase<PxArticulationReducedCoordinate>(names, contexts, args, reader, obj, alloc, collection, ret)
{}
RepXVisitorReader(const RepXVisitorReader<PxArticulationReducedCoordinate>& other)
: RepXVisitorReaderBase<PxArticulationReducedCoordinate>(other)
{}
void handleArticulationLinks(const PxArticulationLinkCollectionProp& inProp)
{
physx::Sn::readProperty(*this, mObj, inProp);
}
};
template<typename TObjType, typename TInfoType>
inline bool readAllProperties( PxRepXInstantiationArgs args, TReaderNameStack& names, PxProfileArray<PxU32>& contexts, XmlReader& reader, TObjType* obj, XmlMemoryAllocator& alloc, PxCollection& collection, TInfoType& info )
{
bool hadError = false;
RepXVisitorReader<TObjType> theReader( names, contexts, args, reader, obj, alloc, collection, hadError);
RepXPropertyFilter<RepXVisitorReader<TObjType> > theOp( theReader );
info.visitBaseProperties( theOp );
info.visitInstanceProperties( theOp );
return !hadError;
}
template<typename TObjType>
inline bool readAllProperties( PxRepXInstantiationArgs args, XmlReader& reader, TObjType* obj, XmlMemoryAllocator& alloc, PxCollection& collection )
{
PxProfileAllocatorWrapper wrapper( alloc.getAllocator() );
TReaderNameStack names( wrapper );
PxProfileArray<PxU32> contexts( wrapper );
PxClassInfoTraits<TObjType> info;
return readAllProperties( args, names, contexts, reader, obj, alloc, collection, info.Info );
}
template<typename TObjType, typename TReaderType, typename TInfoType>
inline void readComplexObj( TReaderType& oldVisitor, TObjType* inObj, TInfoType& info)
{
if(!readAllProperties( oldVisitor.mArgs, oldVisitor.mNames, oldVisitor.mContexts, oldVisitor.mReader, inObj, oldVisitor.mAllocator, oldVisitor.mCollection, info ))
oldVisitor.mHadError = true;
}
template<typename TObjType, typename TReaderType, typename TInfoType>
inline void readComplexObj( TReaderType& oldVisitor, TObjType* inObj, const TInfoType& info)
{
if(!readAllProperties( oldVisitor.mArgs, oldVisitor.mNames, oldVisitor.mContexts, oldVisitor.mReader, inObj, oldVisitor.mAllocator, oldVisitor.mCollection, info ))
oldVisitor.mHadError = true;
}
template<typename TObjType, typename TReaderType>
inline void readComplexObj( TReaderType& oldVisitor, TObjType* inObj, const PxUnknownClassInfo& /*info*/)
{
const char* value = oldVisitor.mReader.getCurrentItemValue();
if ( value && *value )
{
stringToType( value, *inObj );
return;
}
oldVisitor.mHadError = true;
}
template<typename TObjType, typename TReaderType>
inline void readComplexObj( TReaderType& oldVisitor, TObjType* inObj)
{
PxClassInfoTraits<TObjType> info;
if(!readAllProperties( oldVisitor.mArgs, oldVisitor.mNames, oldVisitor.mContexts, oldVisitor.mReader, inObj, oldVisitor.mAllocator, oldVisitor.mCollection, info.Info ))
oldVisitor.mHadError = true;
}
} }
#endif

View File

@ -0,0 +1,897 @@
//
// 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-2021 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_XML_VISITOR_WRITER_H
#define PX_XML_VISITOR_WRITER_H
#include "PsInlineArray.h"
#include "CmPhysXCommon.h"
#include "RepXMetaDataPropertyVisitor.h"
#include "SnPxStreamOperators.h"
#include "SnXmlMemoryPoolStreams.h"
#include "SnXmlWriter.h"
#include "SnXmlImpl.h"
#include "PsFoundation.h"
#include "foundation/PxStrideIterator.h"
namespace physx { namespace Sn {
template<typename TDataType>
inline void writeReference( XmlWriter& writer, PxCollection& inCollection, const char* inPropName, const TDataType* inDatatype )
{
const PxBase* s = static_cast<const PxBase*>( inDatatype ) ;
if( inDatatype && !inCollection.contains( *const_cast<PxBase*>(s) ))
{
Ps::getFoundation().error(PxErrorCode::eINTERNAL_ERROR, __FILE__, __LINE__,
"PxSerialization::serializeCollectionToXml: Reference \"%s\" could not be resolved.", inPropName);
}
PxSerialObjectId theId = 0;
if( s )
{
theId = inCollection.getId( *s );
if( theId == 0 )
theId = static_cast<uint64_t>(reinterpret_cast<size_t>(inDatatype));
}
writer.write( inPropName, PxCreateRepXObject( inDatatype, theId ) );
}
inline void writeProperty( XmlWriter& inWriter, MemoryBuffer& inBuffer, const char* inProp )
{
PxU8 data = 0;
inBuffer.write( &data, sizeof(PxU8) );
inWriter.write( inProp, reinterpret_cast<const char*>( inBuffer.mBuffer ) );
inBuffer.clear();
}
template<typename TDataType>
inline void writeProperty( XmlWriter& inWriter, PxCollection&, MemoryBuffer& inBuffer, const char* inPropName, TDataType inValue )
{
inBuffer << inValue;
writeProperty( inWriter, inBuffer, inPropName );
}
inline void writeProperty( XmlWriter& writer, PxCollection& inCollection, MemoryBuffer& /*inBuffer*/, const char* inPropName, const PxConvexMesh* inDatatype )
{
writeReference( writer, inCollection, inPropName, inDatatype );
}
inline void writeProperty( XmlWriter& writer, PxCollection& inCollection, MemoryBuffer& /*inBuffer*/, const char* inPropName, PxConvexMesh* inDatatype )
{
writeReference( writer, inCollection, inPropName, inDatatype );
}
inline void writeProperty( XmlWriter& writer, PxCollection& inCollection, MemoryBuffer& /*inBuffer*/, const char* inPropName, const PxTriangleMesh* inDatatype )
{
if (inDatatype->getConcreteType() == PxConcreteType::eTRIANGLE_MESH_BVH33)
{
const PxBVH33TriangleMesh* dataType = inDatatype->is<PxBVH33TriangleMesh>();
writeReference(writer, inCollection, inPropName, dataType);
}
else if (inDatatype->getConcreteType() == PxConcreteType::eTRIANGLE_MESH_BVH34)
{
const PxBVH34TriangleMesh* dataType = inDatatype->is<PxBVH34TriangleMesh>();
writeReference(writer, inCollection, inPropName, dataType);
}
else
{
PX_ASSERT(0);
}
}
inline void writeProperty( XmlWriter& writer, PxCollection& inCollection, MemoryBuffer& /*inBuffer*/, const char* inPropName, PxTriangleMesh* inDatatype )
{
if (inDatatype->getConcreteType() == PxConcreteType::eTRIANGLE_MESH_BVH33)
{
PxBVH33TriangleMesh* dataType = inDatatype->is<PxBVH33TriangleMesh>();
writeReference(writer, inCollection, inPropName, dataType);
}
else if (inDatatype->getConcreteType() == PxConcreteType::eTRIANGLE_MESH_BVH34)
{
PxBVH34TriangleMesh* dataType = inDatatype->is<PxBVH34TriangleMesh>();
writeReference(writer, inCollection, inPropName, dataType);
}
else
{
PX_ASSERT(0);
}
}
inline void writeProperty( XmlWriter& writer, PxCollection& inCollection, MemoryBuffer& /*inBuffer*/, const char* inPropName, const PxBVH33TriangleMesh* inDatatype )
{
writeReference( writer, inCollection, inPropName, inDatatype );
}
inline void writeProperty( XmlWriter& writer, PxCollection& inCollection, MemoryBuffer& /*inBuffer*/, const char* inPropName, PxBVH33TriangleMesh* inDatatype )
{
writeReference( writer, inCollection, inPropName, inDatatype );
}
inline void writeProperty( XmlWriter& writer, PxCollection& inCollection, MemoryBuffer& /*inBuffer*/, const char* inPropName, const PxBVH34TriangleMesh* inDatatype )
{
writeReference( writer, inCollection, inPropName, inDatatype );
}
inline void writeProperty( XmlWriter& writer, PxCollection& inCollection, MemoryBuffer& /*inBuffer*/, const char* inPropName, PxBVH34TriangleMesh* inDatatype )
{
writeReference( writer, inCollection, inPropName, inDatatype );
}
inline void writeProperty( XmlWriter& writer, PxCollection& inCollection, MemoryBuffer& /*inBuffer*/, const char* inPropName, const PxHeightField* inDatatype )
{
writeReference( writer, inCollection, inPropName, inDatatype );
}
inline void writeProperty( XmlWriter& writer, PxCollection& inCollection, MemoryBuffer& /*inBuffer*/, const char* inPropName, PxHeightField* inDatatype )
{
writeReference( writer, inCollection, inPropName, inDatatype );
}
inline void writeProperty( XmlWriter& writer, PxCollection& inCollection, MemoryBuffer& /*inBuffer*/, const char* inPropName, const PxRigidActor* inDatatype )
{
writeReference( writer, inCollection, inPropName, inDatatype );
}
inline void writeProperty( XmlWriter& writer, PxCollection& inCollection, MemoryBuffer& /*inBuffer*/, const char* inPropName, PxArticulation* inDatatype )
{
writeReference( writer, inCollection, inPropName, inDatatype );
}
inline void writeProperty(XmlWriter& writer, PxCollection& inCollection, MemoryBuffer& /*inBuffer*/, const char* inPropName, PxArticulationReducedCoordinate* inDatatype)
{
writeReference(writer, inCollection, inPropName, inDatatype);
}
inline void writeProperty( XmlWriter& writer, PxCollection& inCollection, MemoryBuffer& /*inBuffer*/, const char* inPropName, PxRigidActor* inDatatype )
{
writeReference( writer, inCollection, inPropName, inDatatype );
}
inline void writeFlagsProperty( XmlWriter& inWriter, MemoryBuffer& tempBuf, const char* inPropName, PxU32 inFlags, const PxU32ToName* inTable )
{
if ( inTable )
{
PxU32 flagValue( inFlags );
if ( flagValue )
{
for ( PxU32 idx =0; inTable[idx].mName != NULL; ++idx )
{
if ( (inTable[idx].mValue & flagValue) == inTable[idx].mValue )
{
if ( tempBuf.mWriteOffset != 0 )
tempBuf << "|";
tempBuf << inTable[idx].mName;
}
}
writeProperty( inWriter, tempBuf, inPropName );
}
}
}
inline void writeFlagsBuffer( MemoryBuffer& tempBuf, PxU32 flagValue, const PxU32ToName* inTable )
{
PX_ASSERT(inTable);
bool added = false;
if ( flagValue )
{
for ( PxU32 item =0; inTable[item].mName != NULL; ++item )
{
if ( (inTable[item].mValue & flagValue) != 0 )
{
if ( added )
tempBuf << "|";
tempBuf << inTable[item].mName;
added = true;
}
}
}
}
inline void writePxVec3( PxOutputStream& inStream, const PxVec3& inVec ) { inStream << inVec; }
template<typename TDataType>
inline const TDataType& PtrAccess( const TDataType* inPtr, PxU32 inIndex )
{
return inPtr[inIndex];
}
template<typename TDataType>
inline void BasicDatatypeWrite( PxOutputStream& inStream, const TDataType& item ) { inStream << item; }
template<typename TObjType, typename TAccessOperator, typename TWriteOperator>
inline void writeBuffer( XmlWriter& inWriter, MemoryBuffer& inTempBuffer
, PxU32 inObjPerLine, const TObjType* inObjType, TAccessOperator inAccessOperator
, PxU32 inBufSize, const char* inPropName, TWriteOperator inOperator )
{
if ( inBufSize && inObjType )
{
for ( PxU32 idx = 0; idx < inBufSize; ++idx )
{
if ( idx && ( idx % inObjPerLine == 0 ) )
inTempBuffer << "\n\t\t\t";
else
inTempBuffer << " ";
inOperator( inTempBuffer, inAccessOperator( inObjType, idx ) );
}
writeProperty( inWriter, inTempBuffer, inPropName );
}
}
template<typename TDataType, typename TAccessOperator, typename TWriteOperator>
inline void writeStrideBuffer( XmlWriter& inWriter, MemoryBuffer& inTempBuffer
, PxU32 inObjPerLine, PxStrideIterator<const TDataType>& inData, TAccessOperator inAccessOperator
, PxU32 inBufSize, const char* inPropName, PxU32 /*inStride*/, TWriteOperator inOperator )
{
#if PX_SWITCH
const auto *dat = &inData[0];
if (inBufSize && dat != NULL)
#else
if ( inBufSize && &inData[0])
#endif
{
for ( PxU32 idx = 0; idx < inBufSize; ++idx )
{
if ( idx && ( idx % inObjPerLine == 0 ) )
inTempBuffer << "\n\t\t\t";
else
inTempBuffer << " ";
inOperator( inTempBuffer, inAccessOperator( &inData[idx], 0 ) );
}
writeProperty( inWriter, inTempBuffer, inPropName );
}
}
template<typename TDataType, typename TAccessOperator>
inline void writeStrideFlags( XmlWriter& inWriter, MemoryBuffer& inTempBuffer
, PxU32 inObjPerLine, PxStrideIterator<const TDataType>& inData, TAccessOperator /*inAccessOperator*/
, PxU32 inBufSize, const char* inPropName, const PxU32ToName* inTable)
{
#if PX_SWITCH
const auto *dat = &inData[0];
if (inBufSize && dat != NULL)
#else
if ( inBufSize && &inData[0])
#endif
{
for ( PxU32 idx = 0; idx < inBufSize; ++idx )
{
writeFlagsBuffer(inTempBuffer, inData[idx], inTable);
if ( idx && ( idx % inObjPerLine == 0 ) )
inTempBuffer << "\n\t\t\t";
else
inTempBuffer << " ";
}
writeProperty( inWriter, inTempBuffer, inPropName );
}
}
template<typename TDataType, typename TWriteOperator>
inline void writeBuffer( XmlWriter& inWriter, MemoryBuffer& inTempBuffer
, PxU32 inObjPerLine, const TDataType* inBuffer
, PxU32 inBufSize, const char* inPropName, TWriteOperator inOperator )
{
writeBuffer( inWriter, inTempBuffer, inObjPerLine, inBuffer, PtrAccess<TDataType>, inBufSize, inPropName, inOperator );
}
template<typename TEnumType>
inline void writeEnumProperty( XmlWriter& inWriter, const char* inPropName, TEnumType inEnumValue, const PxU32ToName* inConversions )
{
PxU32 theValue = static_cast<PxU32>( inEnumValue );
for ( const PxU32ToName* conv = inConversions; conv->mName != NULL; ++conv )
if ( conv->mValue == theValue ) inWriter.write( inPropName, conv->mName );
}
template<typename TObjType, typename TWriterType, typename TInfoType>
inline void handleComplexObj( TWriterType& oldVisitor, const TObjType* inObj, const TInfoType& info);
template<typename TCollectionType, typename TVisitor, typename TPropType, typename TInfoType >
void handleComplexCollection( TVisitor& visitor, const TPropType& inProp, const char* childName, TInfoType& inInfo )
{
PxU32 count( inProp.size( visitor.mObj ) );
if ( count )
{
Ps::InlineArray<TCollectionType*,5> theData;
theData.resize( count );
inProp.get( visitor.mObj, theData.begin(), count );
for( PxU32 idx =0; idx < count; ++idx )
{
visitor.pushName( childName );
handleComplexObj( visitor, theData[idx], inInfo );
visitor.popName();
}
}
}
template<typename TCollectionType, typename TVisitor, typename TPropType, typename TInfoType >
void handleBufferCollection( TVisitor& visitor, const TPropType& inProp, const char* childName, TInfoType& inInfo )
{
PxU32 count( inProp.size( visitor.mObj ) );
if ( count )
{
Ps::InlineArray<TCollectionType*,5> theData;
theData.resize( count );
inProp.get( visitor.mObj, theData.begin());
for( PxU32 idx =0; idx < count; ++idx )
{
visitor.pushName( childName );
handleComplexObj( visitor, theData[idx], inInfo );
visitor.popName();
}
}
}
template<typename TVisitor>
void handleShapes( TVisitor& visitor, const PxRigidActorShapeCollection& inProp )
{
PxShapeGeneratedInfo theInfo;
PxU32 count( inProp.size( visitor.mObj ) );
if ( count )
{
Ps::InlineArray<PxShape*,5> theData;
theData.resize( count );
inProp.get( visitor.mObj, theData.begin(), count );
for( PxU32 idx = 0; idx < count; ++idx )
{
const PxShape* shape = theData[idx];
visitor.pushName( "PxShape" );
if( !shape->isExclusive() )
{
writeReference( visitor.mWriter, visitor.mCollection, "PxShapeRef", shape );
}
else
{
handleComplexObj( visitor, shape, theInfo );
}
visitor.popName();
}
}
}
template<typename TVisitor>
void handleShapeMaterials( TVisitor& visitor, const PxShapeMaterialsProperty& inProp )
{
PxU32 count( inProp.size( visitor.mObj ) );
if ( count )
{
Ps::InlineArray<PxMaterial*,5> theData;
theData.resize( count );
inProp.get( visitor.mObj, theData.begin(), count );
visitor.pushName( "PxMaterialRef" );
for( PxU32 idx =0; idx < count; ++idx )
writeReference( visitor.mWriter, visitor.mCollection, "PxMaterialRef", theData[idx] );
visitor.popName();
}
}
template<typename TObjType>
struct RepXVisitorWriterBase
{
TNameStack& mNameStack;
XmlWriter& mWriter;
const TObjType* mObj;
MemoryBuffer& mTempBuffer;
PxCollection& mCollection;
RepXVisitorWriterBase( TNameStack& ns, XmlWriter& writer, const TObjType* obj, MemoryBuffer& buf, PxCollection& collection )
: mNameStack( ns )
, mWriter( writer )
, mObj( obj )
, mTempBuffer( buf )
, mCollection( collection )
{
}
RepXVisitorWriterBase( const RepXVisitorWriterBase<TObjType>& other )
: mNameStack( other.mNameStack )
, mWriter( other.mWriter )
, mObj( other.mObj )
, mTempBuffer( other.mTempBuffer )
, mCollection( other.mCollection )
{
}
RepXVisitorWriterBase& operator=( const RepXVisitorWriterBase& ){ PX_ASSERT( false ); return *this; }
void gotoTopName()
{
if ( mNameStack.size() && mNameStack.back().mOpen == false )
{
mWriter.addAndGotoChild( mNameStack.back().mName );
mNameStack.back().mOpen = true;
}
}
void pushName( const char* inName )
{
gotoTopName();
mNameStack.pushBack( inName );
}
void pushBracketedName( const char* inName ) { pushName( inName ); }
void popName()
{
if ( mNameStack.size() )
{
if ( mNameStack.back().mOpen )
mWriter.leaveChild();
mNameStack.popBack();
}
}
const char* topName() const
{
if ( mNameStack.size() ) return mNameStack.back().mName;
PX_ASSERT( false );
return "bad__repx__name";
}
template<typename TAccessorType>
void simpleProperty( PxU32 /*key*/, TAccessorType& inProp )
{
typedef typename TAccessorType::prop_type TPropertyType;
TPropertyType propVal = inProp.get( mObj );
writeProperty( mWriter, mCollection, mTempBuffer, topName(), propVal );
}
template<typename TAccessorType>
void enumProperty( PxU32 /*key*/, TAccessorType& inProp, const PxU32ToName* inConversions )
{
writeEnumProperty( mWriter, topName(), inProp.get( mObj ), inConversions );
}
template<typename TAccessorType>
void flagsProperty( PxU32 /*key*/, const TAccessorType& inProp, const PxU32ToName* inConversions )
{
writeFlagsProperty( mWriter, mTempBuffer, topName(), inProp.get( mObj ), inConversions );
}
template<typename TAccessorType, typename TInfoType>
void complexProperty( PxU32* /*key*/, const TAccessorType& inProp, TInfoType& inInfo )
{
typedef typename TAccessorType::prop_type TPropertyType;
TPropertyType propVal = inProp.get( mObj );
handleComplexObj( *this, &propVal, inInfo );
}
template<typename TAccessorType, typename TInfoType>
void bufferCollectionProperty( PxU32* /*key*/, const TAccessorType& inProp, TInfoType& inInfo )
{
typedef typename TAccessorType::prop_type TPropertyType;
PxU32 count( inProp.size( mObj ) );
Ps::InlineArray<TPropertyType,5> theData;
theData.resize( count );
PxClassInfoTraits<TInfoType> theTraits;
PX_UNUSED(theTraits);
PxU32 numItems = inProp.get( mObj, theData.begin(), count );
PX_ASSERT( numItems == count );
for( PxU32 idx =0; idx < numItems; ++idx )
{
pushName( inProp.name() );
handleComplexObj( *this, &theData[idx], inInfo );
popName();
}
}
template<typename TAccessorType, typename TInfoType>
void extendedIndexedProperty( PxU32* /*key*/, const TAccessorType& inProp, TInfoType& /*inInfo */)
{
typedef typename TAccessorType::prop_type TPropertyType;
PxU32 count( inProp.size( mObj ) );
Ps::InlineArray<TPropertyType,5> theData;
theData.resize( count );
for(PxU32 i = 0; i < count; ++i)
{
char buffer[32] = { 0 };
sprintf( buffer, "id_%u", i );
pushName( buffer );
TPropertyType propVal = inProp.get( mObj, i );
TInfoType& infoType = PxClassInfoTraits<TPropertyType>().Info;
handleComplexObj(*this, &propVal, infoType);
popName();
}
}
template<typename TAccessorType, typename TInfoType>
void PxFixedSizeLookupTableProperty( PxU32* /*key*/, TAccessorType& inProp, TInfoType& /*inInfo */)
{
typedef typename TAccessorType::prop_type TPropertyType;
PxU32 count( inProp.size( mObj ) );
PxU32 index = 0;
for(PxU32 i = 0; i < count; ++i)
{
char buffer[32] = { 0 };
sprintf( buffer, "id_%u", index++ );
pushName( buffer );
TPropertyType propVal = inProp.getX( mObj , i);
writeProperty( mWriter, mCollection, mTempBuffer, topName(), propVal );
popName();
sprintf( buffer, "id_%u", index++ );
pushName( buffer );
propVal = inProp.getY( mObj , i);
writeProperty( mWriter, mCollection, mTempBuffer, topName(), propVal );
popName();
}
}
void handleShapes( const PxRigidActorShapeCollection& inProp )
{
physx::Sn::handleShapes( *this, inProp );
}
void handleShapeMaterials( const PxShapeMaterialsProperty& inProp )
{
physx::Sn::handleShapeMaterials( *this, inProp );
}
void handleRigidActorGlobalPose(const PxRigidActorGlobalPosePropertyInfo& inProp)
{
PxRepXPropertyAccessor<PxPropertyInfoName::PxRigidActor_GlobalPose, PxRigidActor, const PxTransform &, PxTransform> theAccessor( inProp );
simpleProperty(PxPropertyInfoName::PxRigidActor_GlobalPose, theAccessor);
}
};
template<typename TObjType>
struct RepXVisitorWriter : RepXVisitorWriterBase<TObjType>
{
RepXVisitorWriter( TNameStack& ns, XmlWriter& writer, const TObjType* obj, MemoryBuffer& buf, PxCollection& collection )
: RepXVisitorWriterBase<TObjType>( ns, writer, obj, buf, collection )
{
}
RepXVisitorWriter( const RepXVisitorWriter<TObjType>& other )
: RepXVisitorWriterBase<TObjType>( other )
{
}
};
template<>
struct RepXVisitorWriter<PxArticulationLink> : RepXVisitorWriterBase<PxArticulationLink>
{
RepXVisitorWriter( TNameStack& ns, XmlWriter& writer, const PxArticulationLink* obj, MemoryBuffer& buf, PxCollection& collection )
: RepXVisitorWriterBase<PxArticulationLink>( ns, writer, obj, buf, collection )
{
}
RepXVisitorWriter( const RepXVisitorWriter<PxArticulationLink>& other )
: RepXVisitorWriterBase<PxArticulationLink>( other )
{
}
void handleIncomingJoint( const TIncomingJointPropType& prop )
{
const PxArticulationJointBase* jointBase( prop.get( mObj ) );
if ( jointBase )
{
pushName( "Joint" );
const PxArticulationJoint* joint = jointBase->is<PxArticulationJoint>();
if (joint)
{
handleComplexObj( *this, joint, PxArticulationJointGeneratedInfo());
}
else
{
const PxArticulationJointReducedCoordinate* jointReducedCoordinate = jointBase->is<PxArticulationJointReducedCoordinate>();
PX_ASSERT(jointReducedCoordinate);
handleComplexObj( *this, jointReducedCoordinate, PxArticulationJointReducedCoordinateGeneratedInfo());
}
popName();
}
}
};
typedef PxProfileHashMap< const PxSerialObjectId, const PxArticulationLink* > TArticulationLinkLinkMap;
static void recurseAddLinkAndChildren( const PxArticulationLink* inLink, Ps::InlineArray<const PxArticulationLink*, 64>& ioLinks )
{
ioLinks.pushBack( inLink );
Ps::InlineArray<PxArticulationLink*, 8> theChildren;
PxU32 childCount( inLink->getNbChildren() );
theChildren.resize( childCount );
inLink->getChildren( theChildren.begin(), childCount );
for ( PxU32 idx = 0; idx < childCount; ++idx )
recurseAddLinkAndChildren( theChildren[idx], ioLinks );
}
template<>
struct RepXVisitorWriter<PxArticulation> : RepXVisitorWriterBase<PxArticulation>
{
TArticulationLinkLinkMap& mArticulationLinkParents;
RepXVisitorWriter( TNameStack& ns, XmlWriter& writer, const PxArticulation* inArticulation, MemoryBuffer& buf, PxCollection& collection, TArticulationLinkLinkMap* artMap = NULL )
: RepXVisitorWriterBase<PxArticulation>( ns, writer, inArticulation, buf, collection )
, mArticulationLinkParents( *artMap )
{
Ps::InlineArray<PxArticulationLink*, 64, PxProfileWrapperReflectionAllocator<PxArticulationLink*> > linkList( PxProfileWrapperReflectionAllocator<PxArticulationLink*>( buf.mManager->getWrapper() ) );
PxU32 numLinks = inArticulation->getNbLinks();
linkList.resize( numLinks );
inArticulation->getLinks( linkList.begin(), numLinks );
for ( PxU32 idx = 0; idx < numLinks; ++idx )
{
const PxArticulationLink* theLink( linkList[idx] );
Ps::InlineArray<PxArticulationLink*, 64> theChildList;
PxU32 numChildren = theLink->getNbChildren();
theChildList.resize( numChildren );
theLink->getChildren( theChildList.begin(), numChildren );
for ( PxU32 childIdx = 0; childIdx < numChildren; ++childIdx )
mArticulationLinkParents.insert(static_cast<uint64_t>(reinterpret_cast<size_t>(theChildList[childIdx])), theLink );
}
}
RepXVisitorWriter( const RepXVisitorWriter<PxArticulation>& other )
: RepXVisitorWriterBase<PxArticulation>( other )
, mArticulationLinkParents( other.mArticulationLinkParents )
{
}
template<typename TAccessorType, typename TInfoType>
void complexProperty( PxU32* /*key*/, const TAccessorType& inProp, TInfoType& inInfo )
{
typedef typename TAccessorType::prop_type TPropertyType;
TPropertyType propVal = inProp.get( mObj );
handleComplexObj( *this, &propVal, inInfo );
}
void writeArticulationLink( const PxArticulationLink* inLink )
{
pushName( "PxArticulationLink" );
gotoTopName();
const TArticulationLinkLinkMap::Entry* theParentPtr = mArticulationLinkParents.find(static_cast<uint64_t>(reinterpret_cast<size_t>(inLink)) );
if ( theParentPtr != NULL )
writeProperty( mWriter, mCollection, mTempBuffer, "Parent", theParentPtr->second );
writeProperty( mWriter, mCollection, mTempBuffer, "Id", inLink );
PxArticulationLinkGeneratedInfo info;
handleComplexObj( *this, inLink, info );
popName();
}
void handleArticulationLinks( const PxArticulationLinkCollectionProp& inProp )
{
//topologically sort the links as per my discussion with Dilip because
//links aren't guaranteed to have the parents before the children in the
//overall link list and it is unlikely to be done by beta 1.
PxU32 count( inProp.size( mObj ) );
if ( count )
{
Ps::InlineArray<PxArticulationLink*, 64> theLinks;
theLinks.resize( count );
inProp.get( mObj, theLinks.begin(), count );
Ps::InlineArray<const PxArticulationLink*, 64> theSortedLinks;
for ( PxU32 idx = 0; idx < count; ++idx )
{
const PxArticulationLink* theLink( theLinks[idx] );
if ( mArticulationLinkParents.find(static_cast<uint64_t>(reinterpret_cast<size_t>(theLink)) ) == NULL )
recurseAddLinkAndChildren( theLink, theSortedLinks );
}
PX_ASSERT( theSortedLinks.size() == count );
for ( PxU32 idx = 0; idx < count; ++idx )
writeArticulationLink( theSortedLinks[idx] );
popName();
}
}
private:
RepXVisitorWriter<PxArticulation>& operator=(const RepXVisitorWriter<PxArticulation>&);
};
template<>
struct RepXVisitorWriter<PxArticulationReducedCoordinate> : RepXVisitorWriterBase<PxArticulationReducedCoordinate>
{
TArticulationLinkLinkMap& mArticulationLinkParents;
RepXVisitorWriter(TNameStack& ns, XmlWriter& writer, const PxArticulationReducedCoordinate* inArticulation, MemoryBuffer& buf, PxCollection& collection, TArticulationLinkLinkMap* artMap = NULL)
: RepXVisitorWriterBase<PxArticulationReducedCoordinate>(ns, writer, inArticulation, buf, collection)
, mArticulationLinkParents(*artMap)
{
Ps::InlineArray<PxArticulationLink*, 64, PxProfileWrapperReflectionAllocator<PxArticulationLink*> > linkList(PxProfileWrapperReflectionAllocator<PxArticulationLink*>(buf.mManager->getWrapper()));
PxU32 numLinks = inArticulation->getNbLinks();
linkList.resize(numLinks);
inArticulation->getLinks(linkList.begin(), numLinks);
for (PxU32 idx = 0; idx < numLinks; ++idx)
{
const PxArticulationLink* theLink(linkList[idx]);
Ps::InlineArray<PxArticulationLink*, 64> theChildList;
PxU32 numChildren = theLink->getNbChildren();
theChildList.resize(numChildren);
theLink->getChildren(theChildList.begin(), numChildren);
for (PxU32 childIdx = 0; childIdx < numChildren; ++childIdx)
mArticulationLinkParents.insert(static_cast<uint64_t>(reinterpret_cast<size_t>(theChildList[childIdx])), theLink);
}
}
RepXVisitorWriter(const RepXVisitorWriter<PxArticulationReducedCoordinate>& other)
: RepXVisitorWriterBase<PxArticulationReducedCoordinate>(other)
, mArticulationLinkParents(other.mArticulationLinkParents)
{
}
template<typename TAccessorType, typename TInfoType>
void complexProperty(PxU32* /*key*/, const TAccessorType& inProp, TInfoType& inInfo)
{
typedef typename TAccessorType::prop_type TPropertyType;
TPropertyType propVal = inProp.get(mObj);
handleComplexObj(*this, &propVal, inInfo);
}
void writeArticulationLink(const PxArticulationLink* inLink)
{
pushName("PxArticulationLink");
gotoTopName();
const TArticulationLinkLinkMap::Entry* theParentPtr = mArticulationLinkParents.find(static_cast<uint64_t>(reinterpret_cast<size_t>(inLink)));
if (theParentPtr != NULL)
writeProperty(mWriter, mCollection, mTempBuffer, "Parent", theParentPtr->second);
writeProperty(mWriter, mCollection, mTempBuffer, "Id", inLink);
PxArticulationLinkGeneratedInfo info;
handleComplexObj(*this, inLink, info);
popName();
}
void handleArticulationLinks(const PxArticulationLinkCollectionProp& inProp)
{
//topologically sort the links as per my discussion with Dilip because
//links aren't guaranteed to have the parents before the children in the
//overall link list and it is unlikely to be done by beta 1.
PxU32 count(inProp.size(mObj));
if (count)
{
Ps::InlineArray<PxArticulationLink*, 64> theLinks;
theLinks.resize(count);
inProp.get(mObj, theLinks.begin(), count);
Ps::InlineArray<const PxArticulationLink*, 64> theSortedLinks;
for (PxU32 idx = 0; idx < count; ++idx)
{
const PxArticulationLink* theLink(theLinks[idx]);
if (mArticulationLinkParents.find(static_cast<uint64_t>(reinterpret_cast<size_t>(theLink))) == NULL)
recurseAddLinkAndChildren(theLink, theSortedLinks);
}
PX_ASSERT(theSortedLinks.size() == count);
for (PxU32 idx = 0; idx < count; ++idx)
writeArticulationLink(theSortedLinks[idx]);
popName();
}
}
private:
RepXVisitorWriter<PxArticulationReducedCoordinate>& operator=(const RepXVisitorWriter<PxArticulationReducedCoordinate>&);
};
template<>
struct RepXVisitorWriter<PxShape> : RepXVisitorWriterBase<PxShape>
{
RepXVisitorWriter( TNameStack& ns, XmlWriter& writer, const PxShape* obj, MemoryBuffer& buf, PxCollection& collection )
: RepXVisitorWriterBase<PxShape>( ns, writer, obj, buf, collection )
{
}
RepXVisitorWriter( const RepXVisitorWriter<PxShape>& other )
: RepXVisitorWriterBase<PxShape>( other )
{
}
template<typename GeometryType>
inline void writeGeometryProperty( const PxShapeGeometryProperty& inProp, const char* inTypeName )
{
pushName( "Geometry" );
pushName( inTypeName );
GeometryType theType;
inProp.getGeometry( mObj, theType );
PxClassInfoTraits<GeometryType> theTraits;
PxU32 count = theTraits.Info.totalPropertyCount();
if(count)
{
handleComplexObj( *this, &theType, theTraits.Info);
}
else
{
writeProperty(mWriter, mTempBuffer, inTypeName);
}
popName();
popName();
}
void handleGeometryProperty( const PxShapeGeometryProperty& inProp )
{
switch( mObj->getGeometryType() )
{
case PxGeometryType::eSPHERE: writeGeometryProperty<PxSphereGeometry>( inProp, "PxSphereGeometry" ); break;
case PxGeometryType::ePLANE: writeGeometryProperty<PxPlaneGeometry>( inProp, "PxPlaneGeometry" ); break;
case PxGeometryType::eCAPSULE: writeGeometryProperty<PxCapsuleGeometry>( inProp, "PxCapsuleGeometry" ); break;
case PxGeometryType::eBOX: writeGeometryProperty<PxBoxGeometry>( inProp, "PxBoxGeometry" ); break;
case PxGeometryType::eCONVEXMESH: writeGeometryProperty<PxConvexMeshGeometry>( inProp, "PxConvexMeshGeometry" ); break;
case PxGeometryType::eTRIANGLEMESH: writeGeometryProperty<PxTriangleMeshGeometry>( inProp, "PxTriangleMeshGeometry" ); break;
case PxGeometryType::eHEIGHTFIELD: writeGeometryProperty<PxHeightFieldGeometry>( inProp, "PxHeightFieldGeometry" ); break;
case PxGeometryType::eINVALID:
case PxGeometryType::eGEOMETRY_COUNT:
PX_ASSERT( false );
}
}
};
template<typename TObjType>
inline void writeAllProperties( TNameStack& inNameStack, const TObjType* inObj, XmlWriter& writer, MemoryBuffer& buffer, PxCollection& collection )
{
RepXVisitorWriter<TObjType> newVisitor( inNameStack, writer, inObj, buffer, collection );
RepXPropertyFilter<RepXVisitorWriter<TObjType> > theOp( newVisitor );
PxClassInfoTraits<TObjType> info;
info.Info.visitBaseProperties( theOp );
info.Info.visitInstanceProperties( theOp );
}
template<typename TObjType>
inline void writeAllProperties( TNameStack& inNameStack, TObjType* inObj, XmlWriter& writer, MemoryBuffer& buffer, PxCollection& collection )
{
RepXVisitorWriter<TObjType> newVisitor( inNameStack, writer, inObj, buffer, collection );
RepXPropertyFilter<RepXVisitorWriter<TObjType> > theOp( newVisitor );
PxClassInfoTraits<TObjType> info;
info.Info.visitBaseProperties( theOp );
info.Info.visitInstanceProperties( theOp );
}
template<typename TObjType>
inline void writeAllProperties( const TObjType* inObj, XmlWriter& writer, MemoryBuffer& buffer, PxCollection& collection )
{
TNameStack theNames( buffer.mManager->getWrapper() );
writeAllProperties( theNames, inObj, writer, buffer, collection );
}
template<typename TObjType, typename TWriterType, typename TInfoType>
inline void handleComplexObj( TWriterType& oldVisitor, const TObjType* inObj, const TInfoType& /*info*/)
{
writeAllProperties( oldVisitor.mNameStack, inObj, oldVisitor.mWriter, oldVisitor.mTempBuffer, oldVisitor.mCollection );
}
template<typename TObjType, typename TWriterType>
inline void handleComplexObj( TWriterType& oldVisitor, const TObjType* inObj, const PxUnknownClassInfo& /*info*/)
{
writeProperty( oldVisitor.mWriter, oldVisitor.mCollection, oldVisitor.mTempBuffer, oldVisitor.topName(), *inObj );
}
} }
#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-2021 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_XML_WRITER_H
#define PX_XML_WRITER_H
#include "foundation/PxSimpleTypes.h"
namespace physx {
struct PxRepXObject;
/**
* Writer used by extensions to write elements to a file or database
*/
class XmlWriter
{
protected:
virtual ~XmlWriter(){}
public:
/** Write a key-value pair into the current item */
virtual void write( const char* inName, const char* inData ) = 0;
/** Write an object id into the current item */
virtual void write( const char* inName, const PxRepXObject& inLiveObject ) = 0;
/** Add a child that then becomes the current context */
virtual void addAndGotoChild( const char* inName ) = 0;
/** Leave the current child */
virtual void leaveChild() = 0;
};
}
#endif