Fixed over 500 compile warnings. Mostly:

* Unused variables.
* Missing newlines at ends of #included files.
* signed int loop variables where the termination condition is an unsigned 'get number of' function.
* 'NULL' used inappropriately for an integer or character constant (NULL is a pointer)
* abstract base classes with no virtual destructor.
* Floating point constants used to initialise integer variables.
This commit is contained in:
sjbaker
2006-09-23 14:51:54 +00:00
parent ccced9fd82
commit f1627677df
78 changed files with 1629 additions and 1691 deletions

View File

@@ -77,4 +77,5 @@ class OverlappingPairCache : public BroadphaseInterface
};
#endif //OVERLAPPING_PAIR_CACHE_H
#endif //OVERLAPPING_PAIR_CACHE_H

View File

@@ -97,6 +97,7 @@ BroadphaseProxy* SimpleBroadphase::CreateProxy( const SimdVector3& min, const
class RemovingOverlapCallback : public OverlapCallback
{
protected:
virtual bool ProcessOverlap(BroadphasePair& pair)
{
assert(0);
@@ -107,7 +108,7 @@ class RemovePairContainingProxy
{
BroadphaseProxy* m_targetProxy;
protected:
virtual bool ProcessOverlap(BroadphasePair& pair)
{
SimpleBroadphaseProxy* proxy0 = static_cast<SimpleBroadphaseProxy*>(pair.m_pProxy0);

View File

@@ -39,4 +39,5 @@ struct CollisionAlgorithmCreateFunc
return 0;
}
};
#endif //COLLISION_CREATE_FUNC
#endif //COLLISION_CREATE_FUNC

View File

@@ -334,8 +334,6 @@ void CollisionDispatcher::DispatchAllCollisionPairs(OverlappingPairCache* pairCa
{
//m_blockedForChanges = true;
int i;
int dispatcherId = GetUniqueId();
CollisionPairCallback collisionCallback(dispatchInfo,this,dispatcherId);
@@ -344,4 +342,6 @@ void CollisionDispatcher::DispatchAllCollisionPairs(OverlappingPairCache* pairCa
//m_blockedForChanges = false;
}
}

View File

@@ -33,7 +33,6 @@ CollisionWorld::~CollisionWorld()
//clean up remaining objects
std::vector<CollisionObject*>::iterator i;
int index = 0;
for (i=m_collisionObjects.begin();
!(i==m_collisionObjects.end()); i++)

View File

@@ -141,4 +141,6 @@ float CompoundCollisionAlgorithm::CalculateTimeOfImpact(BroadphaseProxy* proxy0,
}
return hitFraction;
}
}

View File

@@ -30,12 +30,12 @@ class Dispatcher;
/// Place holder, not fully implemented yet
class CompoundCollisionAlgorithm : public CollisionAlgorithm
{
Dispatcher* m_dispatcher;
BroadphaseProxy m_compoundProxy;
BroadphaseProxy m_otherProxy;
std::vector<BroadphaseProxy> m_childProxies;
std::vector<CollisionAlgorithm*> m_childCollisionAlgorithms;
Dispatcher* m_dispatcher;
BroadphaseProxy m_compound;
BroadphaseProxy m_other;

View File

@@ -340,7 +340,6 @@ float ConvexConvexAlgorithm::CalculateTimeOfImpact(BroadphaseProxy* proxy0,Broad
CollisionObject* col0 = static_cast<CollisionObject*>(m_box0.m_clientObject);
float squareMot0 = (col0->m_interpolationWorldTransform.getOrigin() - col0->m_worldTransform.getOrigin()).length2();
float squareMot1 = (col1->m_interpolationWorldTransform.getOrigin() - col1->m_worldTransform.getOrigin()).length2();
if (squareMot0 < col0->m_ccdSquareMotionTreshold &&
squareMot0 < col0->m_ccdSquareMotionTreshold)

View File

@@ -13,6 +13,11 @@ SimulationIslandManager::SimulationIslandManager()
{
}
SimulationIslandManager::~SimulationIslandManager()
{
}
void SimulationIslandManager::InitUnionFind(int n)
{
m_unionFind.reset(n);
@@ -131,17 +136,13 @@ bool PersistentManifoldSortPredicate(const PersistentManifold* lhs, const Persis
//
void SimulationIslandManager::BuildAndProcessIslands(Dispatcher* dispatcher,CollisionObjectArray& collisionObjects, IslandCallback* callback)
{
int numBodies = collisionObjects.size();
//we are going to sort the unionfind array, and store the element id in the size
//afterwards, we clean unionfind, to make sure no-one uses it anymore
GetUnionFind().sortIslands();
int numElem = GetUnionFind().getNumElements();
int startIslandIndex=0,endIslandIndex=1;
int endIslandIndex=1;
//update the sleeping state for bodies, if all are sleeping
for (int startIslandIndex=0;startIslandIndex<numElem;startIslandIndex = endIslandIndex)

View File

@@ -29,6 +29,7 @@ class SimulationIslandManager
public:
SimulationIslandManager();
virtual ~SimulationIslandManager();
void InitUnionFind(int n);
@@ -56,3 +57,4 @@ public:
};
#endif //SIMULATION_ISLAND_MANAGER_H

View File

@@ -51,4 +51,5 @@ public:
};
#endif //SPHERE_SPHERE_COLLISION_ALGORITHM_H
#endif //SPHERE_SPHERE_COLLISION_ALGORITHM_H

View File

@@ -31,11 +31,6 @@ class BoxShape: public PolyhedralConvexShape
public:
virtual ~BoxShape()
{
}
SimdVector3 GetHalfExtents() const;
//{ return m_boxHalfExtents1 * m_localScaling;}
//const SimdVector3& GetHalfExtents() const{ return m_boxHalfExtents1;}
@@ -265,3 +260,4 @@ public:
};
#endif //OBB_BOX_MINKOWSKI_H

View File

@@ -25,11 +25,9 @@ subject to the following restrictions:
///CollisionShape provides generic interface for collidable objects
class CollisionShape
{
public:
CollisionShape()
:m_tempDebug(0)
CollisionShape() :m_tempDebug(0)
{
}
virtual ~CollisionShape()

View File

@@ -15,11 +15,6 @@ subject to the following restrictions:
#include "ConvexShape.h"
ConvexShape::~ConvexShape()
{
}
ConvexShape::ConvexShape()
:m_collisionMargin(CONVEX_DISTANCE_MARGIN),
m_localScaling(1.f,1.f,1.f)

View File

@@ -36,8 +36,6 @@ class ConvexShape : public CollisionShape
public:
ConvexShape();
virtual ~ConvexShape();
virtual SimdVector3 LocalGetSupportingVertex(const SimdVector3& vec)const;
virtual SimdVector3 LocalGetSupportingVertexWithoutMargin(const SimdVector3& vec) const= 0;

View File

@@ -40,8 +40,8 @@ public:
LocalSupportVertexCallback(const SimdVector3& supportVecLocal)
: m_supportVertexLocal(0.f,0.f,0.f),
m_supportVecLocal(supportVecLocal),
m_maxDot(-1e30f)
m_maxDot(-1e30f),
m_supportVecLocal(supportVecLocal)
{
}
@@ -72,7 +72,6 @@ public:
SimdVector3 ConvexTriangleMeshShape::LocalGetSupportingVertexWithoutMargin(const SimdVector3& vec0)const
{
SimdVector3 supVec(0.f,0.f,0.f);
SimdScalar newDot,maxDot = -1e30f;
SimdVector3 vec = vec0;
SimdScalar lenSqr = vec.length2();
@@ -95,7 +94,6 @@ SimdVector3 ConvexTriangleMeshShape::LocalGetSupportingVertexWithoutMargin(const
void ConvexTriangleMeshShape::BatchedUnitVectorGetSupportingVertexWithoutMargin(const SimdVector3* vectors,SimdVector3* supportVerticesOut,int numVectors) const
{
SimdScalar newDot;
//use 'w' component of supportVerticesOut?
{
for (int i=0;i<numVectors;i++)

View File

@@ -46,4 +46,6 @@ public:
#endif //CONVEX_TRIANGLEMESH_SHAPE_H
#endif //CONVEX_TRIANGLEMESH_SHAPE_H

View File

@@ -28,7 +28,7 @@ class PolyhedralConvexShape : public ConvexShape
public:
PolyhedralConvexShape();
//brute force implementations
virtual SimdVector3 LocalGetSupportingVertexWithoutMargin(const SimdVector3& vec)const;
virtual void BatchedUnitVectorGetSupportingVertexWithoutMargin(const SimdVector3* vectors,SimdVector3* supportVerticesOut,int numVectors) const;

View File

@@ -28,8 +28,8 @@ protected:
SimdVector3 m_localAabbMax;
SimdVector3 m_planeNormal;
SimdScalar m_planeConstant;
SimdVector3 m_localScaling;
SimdScalar m_planeConstant;
public:
StaticPlaneShape(const SimdVector3& planeNormal,SimdScalar planeConstant);

View File

@@ -33,8 +33,6 @@ void StridingMeshInterface::InternalProcessAllTriangles(InternalTriangleIndexCal
int stride,numverts,numtriangles;
int gfxindex;
SimdVector3 triangle[3];
int tempIndices[3] = {0,0,0};
int graphicsindex=0;
float* graphicsbase;
SimdVector3 meshScaling = getScaling();

View File

@@ -176,7 +176,6 @@ float resolveSingleFriction(
const SimdVector3& pos1 = contactPoint.GetPositionWorldOnA();
const SimdVector3& pos2 = contactPoint.GetPositionWorldOnB();
const SimdVector3& normal = contactPoint.m_normalWorldOnB;
SimdVector3 rel_pos1 = pos1 - body1.getCenterOfMassPosition();
SimdVector3 rel_pos2 = pos2 - body2.getCenterOfMassPosition();
@@ -192,7 +191,6 @@ float resolveSingleFriction(
{
//apply friction in the 2 tangential directions
SimdScalar relaxation = solverInfo.m_damping;
{
// 1st tangent
SimdVector3 vel1 = body1.getVelocityInLocalPoint(rel_pos1);

View File

@@ -243,6 +243,7 @@ SimdScalar Generic6DofConstraint::ComputeAngle(int axis) const
angle = SimdAtan2( s, c );
}
break;
default: assert ( 0 ) ; break ;
}
return angle;

View File

@@ -257,8 +257,6 @@ void RaycastVehicle::UpdateVehicle( SimdScalar step )
for (wheelIt = m_wheelInfo.begin();
!(wheelIt == m_wheelInfo.end());wheelIt++,i++)
{
WheelInfo& wheelInfo = *wheelIt;
SimdScalar depth;
depth = Raycast( *wheelIt );
}

View File

@@ -47,7 +47,6 @@ void BspConverter::convertBsp(BspLoader& bspLoader,float scaling)
{
printf("Reading bspLeaf %i from total %i (%f procent)\n",i, bspLoader.m_numleafs,(100.f*(float)i/float(bspLoader.m_numleafs)) );
bool isValid = false;
bool isValidBrush = false;
BSPLeaf& leaf = bspLoader.m_dleafs[i];
@@ -96,11 +95,6 @@ void BspConverter::convertBsp(BspLoader& bspLoader,float scaling)
}
}
}
else
{
int i=0;
}
}
}
@@ -205,8 +199,6 @@ void BspConverter::convertBsp(BspLoader& bspLoader,float scaling)
void BspConverter::getVerticesFromPlaneEquations(const std::vector<SimdVector3>& planeEquations , std::vector<SimdVector3>& verticesOut )
{
float minimumDotProduct = 1e30f;
const int numbrushes = planeEquations.size();
// brute force:
for (int i=0;i<numbrushes;i++)
@@ -279,4 +271,4 @@ bool BspConverter::isInside(const std::vector<SimdVector3>& planeEquations, cons
}
return true;
}
}

View File

@@ -37,4 +37,5 @@ class BspConverter
};
#endif //BSP_CONVERTER_H
#endif //BSP_CONVERTER_H

View File

@@ -261,7 +261,7 @@ char* makeExeToBspFilename(const char* lpCmdLine)
// displays the first filename
const char *in = lpCmdLine;
char* out = cleaned_filename;
*out = NULL;
*out = '\0';
// If the first character is a ", skip it (filenames with spaces in them are quoted)
if(*in == '\"')
{
@@ -276,7 +276,7 @@ char* makeExeToBspFilename(const char* lpCmdLine)
break;
// If we hit a null or a quote, stop copying. This will get just the first filename.
if(*in == NULL || *in == '\"')
if(*in == '\0' || *in == '\"')
break;
// Copy while swapping backslashes for forward ones
if(*in == '\\')

View File

@@ -34,4 +34,6 @@ class BspDemo : public DemoApplication
};
#endif //BSP_DEMO_H
#endif //BSP_DEMO_H

View File

@@ -710,4 +710,5 @@ const BSPEntity * BspLoader::getEntityByValue( const char* name, const char* val
}
}
return entity;
}
}

View File

@@ -269,8 +269,7 @@ void CcdPhysicsDemo::initPhysics()
{
CollisionDispatcher* dispatcher = new CollisionDispatcher();
ParallelIslandDispatcher* dispatcher2 = new ParallelIslandDispatcher();
SimdVector3 worldAabbMin(-10000,-10000,-10000);
SimdVector3 worldAabbMax(10000,10000,10000);

View File

@@ -32,4 +32,5 @@ class CcdPhysicsDemo : public DemoApplication
};
#endif //CCD_PHYSICS_DEMO_H
#endif //CCD_PHYSICS_DEMO_H

File diff suppressed because it is too large Load Diff

View File

@@ -87,4 +87,6 @@ public:
};
#endif //COLLADA_CONVERTER_H
#endif //COLLADA_CONVERTER_H

View File

@@ -37,4 +37,5 @@ class ColladaDemo : public DemoApplication
};
#endif //COLLADA_PHYSICS_DEMO_H
#endif //COLLADA_PHYSICS_DEMO_H

View File

@@ -45,8 +45,8 @@ GL_Simplex1to4 simplex;
PolyhedralConvexShape* shapePtr[maxNumObjects];
SimdTransform tr[numObjects];
int screenWidth = 640.f;
int screenHeight = 480.f;
int screenWidth = 640;
int screenHeight = 480;
void DrawRasterizerLine(float const* , float const*, int)
{

View File

@@ -33,4 +33,5 @@ class CollisionDemo : public DemoApplication
}
};
#endif //COLLISION_DEMO_H
#endif //COLLISION_DEMO_H

View File

@@ -45,8 +45,8 @@ GL_Simplex1to4 simplex;
CollisionObject objects[maxNumObjects];
CollisionWorld* collisionWorld = 0;
int screenWidth = 640.f;
int screenHeight = 480.f;
int screenWidth = 640;
int screenHeight = 480;
int main(int argc,char** argv)
@@ -74,8 +74,8 @@ void CollisionInterfaceDemo::initPhysics()
objects[0].m_worldTransform.setBasis(basisA);
objects[1].m_worldTransform.setBasis(basisB);
SimdPoint3 points0[3]={SimdPoint3(1,0,0),SimdPoint3(0,1,0),SimdPoint3(0,0,1)};
SimdPoint3 points1[5]={SimdPoint3(1,0,0),SimdPoint3(0,1,0),SimdPoint3(0,0,1),SimdPoint3(0,0,-1),SimdPoint3(-1,-1,0)};
//SimdPoint3 points0[3]={SimdPoint3(1,0,0),SimdPoint3(0,1,0),SimdPoint3(0,0,1)};
//SimdPoint3 points1[5]={SimdPoint3(1,0,0),SimdPoint3(0,1,0),SimdPoint3(0,0,1),SimdPoint3(0,0,-1),SimdPoint3(-1,-1,0)};
BoxShape* boxA = new BoxShape(SimdVector3(1,1,1));
BoxShape* boxB = new BoxShape(SimdVector3(0.5,0.5,0.5));

View File

@@ -32,4 +32,5 @@ class CollisionInterfaceDemo : public DemoApplication
};
#endif //COLLISION_INTERFACE_DEMO_H
#endif //COLLISION_INTERFACE_DEMO_H

View File

@@ -33,4 +33,5 @@ class ConcaveDemo : public DemoApplication
};
#endif //CONCAVE_DEMO_H
#endif //CONCAVE_DEMO_H

View File

@@ -164,7 +164,7 @@ void ConcaveDemo::initPhysics()
ConstraintSolver* solver = new SequentialImpulseConstraintSolver;
// ConstraintSolver* solver = new SequentialImpulseConstraintSolver;
CollisionDispatcher* dispatcher = new CollisionDispatcher();
@@ -188,7 +188,7 @@ void ConcaveDemo::initPhysics()
{
CollisionShape* boxShape = new BoxShape(SimdVector3(1,1,1));
startTransform.setOrigin(SimdVector3(2*i,1,1));
CcdPhysicsController* boxRigidBody = LocalCreatePhysicsObject(true, 1, startTransform,boxShape);
LocalCreatePhysicsObject(true, 1, startTransform,boxShape);
}
}
m_physicsEnvironmentPtr->setGravity(-1,-10,1);

View File

@@ -60,9 +60,7 @@ int main(int argc,char** argv)
void ConstraintDemo::initPhysics()
{
ConstraintSolver* solver = new SequentialImpulseConstraintSolver;
//ConstraintSolver* solver = new SequentialImpulseConstraintSolver;
//ConstraintSolver* solver = new OdeConstraintSolver;
CollisionDispatcher* dispatcher = new CollisionDispatcher();

View File

@@ -33,4 +33,5 @@ class ConstraintDemo : public DemoApplication
}
};
#endif //CONSTRAINT_DEMO_H
#endif //CONSTRAINT_DEMO_H

View File

@@ -33,4 +33,5 @@ class ContinuousConvexCollisionDemo : public DemoApplication
}
};
#endif //CONTINUOUS_CONVEX_COLLISION_DEMO_H
#endif //CONTINUOUS_CONVEX_COLLISION_DEMO_H

View File

@@ -58,8 +58,8 @@ SimdTransform fromTrans[maxNumObjects];
SimdTransform toTrans[maxNumObjects];
int screenWidth = 640.f;
int screenHeight = 480.f;
int screenWidth = 640;
int screenHeight = 480;
int main(int argc,char** argv)
@@ -158,16 +158,9 @@ void ContinuousConvexCollisionDemo::displayCallback(void) {
{
i=0;//for (i=1;i<numObjects;i++)
{
SimdScalar dt = 1.f;
SimdScalar boundingRadius = shapePtr[i]->GetAngularMotionDisc();
SimdScalar angspeed = angVels[i].length() * boundingRadius * dt;
SimdScalar linspeed = linVels[i].length() * dt;
SimdScalar totalspeed = angspeed + linspeed;
//for each object, subdivide the from/to transform in 10 equal steps
int numSubSteps = 10.f;
int numSubSteps = 10;
for (int s=0;s<10;s++)
{
SimdScalar subStep = s * 1.f/(float)numSubSteps;
@@ -188,8 +181,6 @@ void ContinuousConvexCollisionDemo::displayCallback(void) {
}
int shapeIndex = 1;
SimdMatrix3x3 mat;
mat.setEulerZYX(yaw,pitch,roll);
SimdQuaternion orn;

View File

@@ -76,10 +76,6 @@ GLDebugDrawer debugDrawer;
int main(int argc,char** argv)
{
int i;
char* filename = "file.obj";
@@ -308,7 +304,7 @@ void ConvexDecompositionDemo::initPhysics(const char* filename)
//convexDecomposition.performConvexDecomposition(desc);
ConvexBuilder cb(desc.mCallback);
int ret = cb.process(desc);
cb.process(desc);
if (outputFile)
fclose(outputFile);

View File

@@ -35,4 +35,6 @@ class ConvexDecompositionDemo : public DemoApplication
};
#endif //CONVEX_DECOMPOSITION_DEMO_H
#endif //CONVEX_DECOMPOSITION_DEMO_H

View File

@@ -128,7 +128,7 @@ void ForkLiftDemo::setupPhysics()
{
CollisionDispatcher* dispatcher = new CollisionDispatcher();
ParallelIslandDispatcher* dispatcher2 = new ParallelIslandDispatcher();
//ParallelIslandDispatcher* dispatcher2 = new ParallelIslandDispatcher();
SimdVector3 worldAabbMin(-30000,-30000,-30000);
SimdVector3 worldAabbMax(30000,30000,30000);

View File

@@ -50,8 +50,8 @@ const int numObjects = 2;
PolyhedralConvexShape* shapePtr[maxNumObjects];
SimdTransform tr[numObjects];
int screenWidth = 640.f;
int screenHeight = 480.f;
int screenWidth = 640;
int screenHeight = 480;
void DrawRasterizerLine(float const* , float const*, int)
{

View File

@@ -33,4 +33,5 @@ class LinearConvexCastDemo : public DemoApplication
}
};
#endif //LINEAR_CONVEX_CAST_DEMO_H
#endif //LINEAR_CONVEX_CAST_DEMO_H

View File

@@ -75,7 +75,7 @@ void BMF_BitmapFont::DrawString(const char* str)
glGetIntegerv(GL_UNPACK_ALIGNMENT, &alignment);
glPixelStorei(GL_UNPACK_ALIGNMENT, 1);
while (c = (unsigned char) *str++) {
while ((c = (unsigned char) *str++)) {
BMF_CharData & cd = m_fontData->chars[c];
if (cd.data_offset==-1) {
@@ -98,7 +98,7 @@ int BMF_BitmapFont::GetStringWidth(char* str)
unsigned char c;
int length = 0;
while (c = (unsigned char) *str++) {
while ((c = (unsigned char) *str++)) {
length += m_fontData->chars[c].advance;
}
@@ -182,7 +182,7 @@ void BMF_BitmapFont::DrawStringTexture(char *str, float x, float y, float z)
int baseLine = -(m_fontData->ymin);
glBegin(GL_QUADS);
while (c = (unsigned char) *str++) {
while ((c = (unsigned char) *str++)) {
BMF_CharData & cd = m_fontData->chars[c];
if (cd.data_offset != -1) {

View File

@@ -167,4 +167,5 @@ class DemoApplication
};
#endif //DEMO_APPLICATION_H
#endif //DEMO_APPLICATION_H

View File

@@ -151,7 +151,6 @@ void GL_ShapeDrawer::DrawOpenGL(float* m, const CollisionShape* shape, const Sim
case TRIANGLE_SHAPE_PROXYTYPE:
case TETRAHEDRAL_SHAPE_PROXYTYPE:
{
const BU_Simplex1to4* tetra = static_cast<const BU_Simplex1to4*>(shape);
//todo:
// useWireframeFallback = false;
break;

View File

@@ -51,21 +51,14 @@ void GL_Simplex1to4::CalcClosest(float* m)
bool res;
SimdVector3 v;
SimdPoint3 pBuf[4];
SimdPoint3 qBuf[4];
SimdPoint3 yBuf[4];
for (int i=0;i<m_numVertices;i++)
{
v = tr(m_vertices[i]);
m_simplexSolver->addVertex(v,v,SimdPoint3(0.f,0.f,0.f));
res = m_simplexSolver->closest(v);
int res = m_simplexSolver->getSimplex(pBuf, qBuf, yBuf);
}
//draw v?
glDisable(GL_LIGHTING);
glBegin(GL_LINES);

View File

@@ -42,7 +42,7 @@ void RenderTexture::Printf(char* str, BMF_FontData* fontData, int startx,int sta
unsigned char c;
int rasterposx = startx;
int rasterposy = starty;
while (c = (unsigned char) *str++) {
while ((c = (unsigned char) *str++)) {
BMF_CharData & cd = fontData->chars[c];
if (cd.data_offset!=-1) {

View File

@@ -110,9 +110,8 @@ void Raytracer::initPhysics()
SimdVector3(-0.5f, 0.6f, 0.f),
SimdVector3(0.f, 0.f, 0.f)
};
SimdScalar radi[NUM_SPHERES] = { 0.35f,0.35f,0.45f,0.40f,0.40f };
MultiSphereShape* multiSphereShape = new MultiSphereShape(inertiaHalfExtents,positions,radi,NUM_SPHERES);
// MultiSphereShape* multiSphereShape = new MultiSphereShape(inertiaHalfExtents,positions,radi,NUM_SPHERES);
ConvexHullShape* convexHullShape = new ConvexHullShape(positions,3);

View File

@@ -33,4 +33,6 @@ class Raytracer : public DemoApplication
}
};
#endif //RAYTRACER_H
#endif //RAYTRACER_H

View File

@@ -34,8 +34,8 @@ VoronoiSimplexSolver simplexSolver;
float yaw=0.f,pitch=0.f,roll=0.f;
const int maxNumObjects = 4;
const int numObjects = 1;
int screenWidth = 640.f;
int screenHeight = 480.f;
int screenWidth = 640;
int screenHeight = 480;
/// simplex contains the vertices, and some extra code to draw and debug
GL_Simplex1to4 simplex;
@@ -115,4 +115,6 @@ void SimplexDemo::initPhysics()
SimdTransform tr;
tr.setIdentity();
}
}

View File

@@ -33,4 +33,6 @@ class SimplexDemo : public DemoApplication
}
};
#endif //SIMPLEX_DEMO_H
#endif //SIMPLEX_DEMO_H

View File

@@ -137,7 +137,7 @@ void UserCollisionAlgorithm::initPhysics()
ConstraintSolver* solver = new SequentialImpulseConstraintSolver;
//ConstraintSolver* solver = new SequentialImpulseConstraintSolver;
CollisionDispatcher* dispatcher = new CollisionDispatcher();
@@ -163,7 +163,7 @@ void UserCollisionAlgorithm::initPhysics()
{
CollisionShape* sphereShape = new SphereShape(1);
startTransform.setOrigin(SimdVector3(1,2*i,1));
CcdPhysicsController* boxRigidBody = LocalCreatePhysicsObject(true, 1, startTransform,sphereShape);
LocalCreatePhysicsObject(true, 1, startTransform,sphereShape);
}
}
m_physicsEnvironmentPtr->setGravity(-1,-10,1);

View File

@@ -32,4 +32,5 @@ class UserCollisionAlgorithm : public DemoApplication
};
#endif //USER_COLLISION_ALGORITHM_DEMO_H
#endif //USER_COLLISION_ALGORITHM_DEMO_H

View File

@@ -8,6 +8,10 @@
#include "fitsphere.h"
#include "bestfitobb.h"
unsigned int MAXDEPTH = 8 ;
float CONCAVE_PERCENT = 1.0f ;
float MERGE_PERCENT = 2.0f ;
CHull::CHull(const ConvexResult &result)
{
mResult = new ConvexResult(result);
@@ -147,8 +151,6 @@ CHull * ConvexBuilder::canMerge(CHull *a,CHull *b)
if (!tcount)
return 0;
unsigned int *idx = &indices[0];
HullResult hresult;
HullLibrary hl;
HullDesc desc;

View File

@@ -79,7 +79,7 @@ class ConvexBuilder : public ConvexDecompInterface
public:
ConvexBuilder(ConvexDecompInterface *callback);
~ConvexBuilder(void);
virtual ~ConvexBuilder(void);
bool isDuplicate(unsigned int i1,unsigned int i2,unsigned int i3,
unsigned int ci1,unsigned int ci2,unsigned int ci3);
@@ -108,3 +108,4 @@ public:
};
#endif //CONVEX_BUILDER_H

View File

@@ -337,9 +337,6 @@ void calcConvexDecomposition(unsigned int vcount,
}
}
unsigned int fsize = ifront.size()/3;
unsigned int bsize = iback.size()/3;
// ok... here we recursively call
if ( ifront.size() )
{

View File

@@ -1,219 +1,219 @@
#ifndef CONVEX_DECOMPOSITION_H
#define CONVEX_DECOMPOSITION_H
/*----------------------------------------------------------------------
Copyright (c) 2004 Open Dynamics Framework Group
www.physicstools.org
All rights reserved.
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 the Open Dynamics Framework Group 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 AND CONTRIBUTORS '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 INTEL 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.
-----------------------------------------------------------------------*/
// http://codesuppository.blogspot.com
//
// mailto: jratcliff@infiniplex.net
//
// http://www.amillionpixels.us
//
#ifdef WIN32
#include <memory.h> //memcpy
#endif
#include <string.h>
#ifndef CONVEX_DECOMPOSITION_H
#define CONVEX_DECOMPOSITION_H
/*----------------------------------------------------------------------
Copyright (c) 2004 Open Dynamics Framework Group
www.physicstools.org
All rights reserved.
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 the Open Dynamics Framework Group 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 AND CONTRIBUTORS '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 INTEL 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.
-----------------------------------------------------------------------*/
// http://codesuppository.blogspot.com
//
// mailto: jratcliff@infiniplex.net
//
// http://www.amillionpixels.us
//
#ifdef WIN32
#include <memory.h> //memcpy
#endif
#include <string.h>
#include <stdio.h>
static unsigned int MAXDEPTH=8;
static float CONCAVE_PERCENT=1.0f;
static float MERGE_PERCENT=2.0f;
#include <vector>
typedef std::vector< unsigned int > UintVector;
namespace ConvexDecomposition
{
class ConvexResult
{
public:
ConvexResult(void)
{
mHullVcount = 0;
mHullVertices = 0;
mHullTcount = 0;
mHullIndices = 0;
}
ConvexResult(unsigned int hvcount,const float *hvertices,unsigned int htcount,const unsigned int *hindices)
{
mHullVcount = hvcount;
if ( mHullVcount )
{
mHullVertices = new float[mHullVcount*sizeof(float)*3];
memcpy(mHullVertices, hvertices, sizeof(float)*3*mHullVcount );
}
else
{
mHullVertices = 0;
}
mHullTcount = htcount;
if ( mHullTcount )
{
mHullIndices = new unsigned int[sizeof(unsigned int)*mHullTcount*3];
memcpy(mHullIndices,hindices, sizeof(unsigned int)*mHullTcount*3 );
}
else
{
mHullIndices = 0;
}
}
ConvexResult(const ConvexResult &r)
{
mHullVcount = r.mHullVcount;
if ( mHullVcount )
{
mHullVertices = new float[mHullVcount*sizeof(float)*3];
memcpy(mHullVertices, r.mHullVertices, sizeof(float)*3*mHullVcount );
}
else
{
mHullVertices = 0;
}
mHullTcount = r.mHullTcount;
if ( mHullTcount )
{
mHullIndices = new unsigned int[sizeof(unsigned int)*mHullTcount*3];
memcpy(mHullIndices, r.mHullIndices, sizeof(unsigned int)*mHullTcount*3 );
}
else
{
mHullIndices = 0;
}
}
~ConvexResult(void)
{
delete mHullVertices;
delete mHullIndices;
}
// the convex hull.
unsigned int mHullVcount;
float * mHullVertices;
unsigned int mHullTcount;
unsigned int *mHullIndices;
float mHullVolume; // the volume of the convex hull.
float mOBBSides[3]; // the width, height and breadth of the best fit OBB
float mOBBCenter[3]; // the center of the OBB
float mOBBOrientation[4]; // the quaternion rotation of the OBB.
float mOBBTransform[16]; // the 4x4 transform of the OBB.
float mOBBVolume; // the volume of the OBB
float mSphereRadius; // radius and center of best fit sphere
float mSphereCenter[3];
float mSphereVolume; // volume of the best fit sphere
};
class ConvexDecompInterface
{
public:
virtual void ConvexDebugTri(const float *p1,const float *p2,const float *p3,unsigned int color) { };
virtual void ConvexDebugPoint(const float *p,float dist,unsigned int color) { };
virtual void ConvexDebugBound(const float *bmin,const float *bmax,unsigned int color) { };
virtual void ConvexDebugOBB(const float *sides, const float *matrix,unsigned int color) { };
virtual void ConvexDecompResult(ConvexResult &result) = 0;
};
// just to avoid passing a zillion parameters to the method the
// options are packed into this descriptor.
class DecompDesc
{
public:
DecompDesc(void)
{
mVcount = 0;
mVertices = 0;
mTcount = 0;
mIndices = 0;
mDepth = 5;
mCpercent = 5;
mPpercent = 5;
mMaxVertices = 32;
mSkinWidth = 0;
mCallback = 0;
}
// describes the input triangle.
unsigned int mVcount; // the number of vertices in the source mesh.
const float *mVertices; // start of the vertex position array. Assumes a stride of 3 floats.
unsigned int mTcount; // the number of triangles in the source mesh.
unsigned int *mIndices; // the indexed triangle list array (zero index based)
// options
unsigned int mDepth; // depth to split, a maximum of 10, generally not over 7.
float mCpercent; // the concavity threshold percentage. 0=20 is reasonable.
float mPpercent; // the percentage volume conservation threshold to collapse hulls. 0-30 is reasonable.
// hull output limits.
unsigned int mMaxVertices; // maximum number of vertices in the output hull. Recommended 32 or less.
float mSkinWidth; // a skin width to apply to the output hulls.
ConvexDecompInterface *mCallback; // the interface to receive back the results.
};
// perform approximate convex decomposition on a mesh.
unsigned int performConvexDecomposition(const DecompDesc &desc); // returns the number of hulls produced.
void calcConvexDecomposition(unsigned int vcount,
const float *vertices,
unsigned int tcount,
const unsigned int *indices,
ConvexDecompInterface *callback,
float masterVolume,
unsigned int depth);
};
#endif
extern unsigned int MAXDEPTH ;
extern float CONCAVE_PERCENT ;
extern float MERGE_PERCENT ;
#include <vector>
typedef std::vector< unsigned int > UintVector;
namespace ConvexDecomposition
{
class ConvexResult
{
public:
ConvexResult(void)
{
mHullVcount = 0;
mHullVertices = 0;
mHullTcount = 0;
mHullIndices = 0;
}
ConvexResult(unsigned int hvcount,const float *hvertices,unsigned int htcount,const unsigned int *hindices)
{
mHullVcount = hvcount;
if ( mHullVcount )
{
mHullVertices = new float[mHullVcount*sizeof(float)*3];
memcpy(mHullVertices, hvertices, sizeof(float)*3*mHullVcount );
}
else
{
mHullVertices = 0;
}
mHullTcount = htcount;
if ( mHullTcount )
{
mHullIndices = new unsigned int[sizeof(unsigned int)*mHullTcount*3];
memcpy(mHullIndices,hindices, sizeof(unsigned int)*mHullTcount*3 );
}
else
{
mHullIndices = 0;
}
}
ConvexResult(const ConvexResult &r)
{
mHullVcount = r.mHullVcount;
if ( mHullVcount )
{
mHullVertices = new float[mHullVcount*sizeof(float)*3];
memcpy(mHullVertices, r.mHullVertices, sizeof(float)*3*mHullVcount );
}
else
{
mHullVertices = 0;
}
mHullTcount = r.mHullTcount;
if ( mHullTcount )
{
mHullIndices = new unsigned int[sizeof(unsigned int)*mHullTcount*3];
memcpy(mHullIndices, r.mHullIndices, sizeof(unsigned int)*mHullTcount*3 );
}
else
{
mHullIndices = 0;
}
}
~ConvexResult(void)
{
delete mHullVertices;
delete mHullIndices;
}
// the convex hull.
unsigned int mHullVcount;
float * mHullVertices;
unsigned int mHullTcount;
unsigned int *mHullIndices;
float mHullVolume; // the volume of the convex hull.
float mOBBSides[3]; // the width, height and breadth of the best fit OBB
float mOBBCenter[3]; // the center of the OBB
float mOBBOrientation[4]; // the quaternion rotation of the OBB.
float mOBBTransform[16]; // the 4x4 transform of the OBB.
float mOBBVolume; // the volume of the OBB
float mSphereRadius; // radius and center of best fit sphere
float mSphereCenter[3];
float mSphereVolume; // volume of the best fit sphere
};
class ConvexDecompInterface
{
public:
virtual void ConvexDebugTri(const float *p1,const float *p2,const float *p3,unsigned int color) { };
virtual void ConvexDebugPoint(const float *p,float dist,unsigned int color) { };
virtual void ConvexDebugBound(const float *bmin,const float *bmax,unsigned int color) { };
virtual void ConvexDebugOBB(const float *sides, const float *matrix,unsigned int color) { };
virtual void ConvexDecompResult(ConvexResult &result) = 0;
};
// just to avoid passing a zillion parameters to the method the
// options are packed into this descriptor.
class DecompDesc
{
public:
DecompDesc(void)
{
mVcount = 0;
mVertices = 0;
mTcount = 0;
mIndices = 0;
mDepth = 5;
mCpercent = 5;
mPpercent = 5;
mMaxVertices = 32;
mSkinWidth = 0;
mCallback = 0;
}
// describes the input triangle.
unsigned int mVcount; // the number of vertices in the source mesh.
const float *mVertices; // start of the vertex position array. Assumes a stride of 3 floats.
unsigned int mTcount; // the number of triangles in the source mesh.
unsigned int *mIndices; // the indexed triangle list array (zero index based)
// options
unsigned int mDepth; // depth to split, a maximum of 10, generally not over 7.
float mCpercent; // the concavity threshold percentage. 0=20 is reasonable.
float mPpercent; // the percentage volume conservation threshold to collapse hulls. 0-30 is reasonable.
// hull output limits.
unsigned int mMaxVertices; // maximum number of vertices in the output hull. Recommended 32 or less.
float mSkinWidth; // a skin width to apply to the output hulls.
ConvexDecompInterface *mCallback; // the interface to receive back the results.
};
// perform approximate convex decomposition on a mesh.
unsigned int performConvexDecomposition(const DecompDesc &desc); // returns the number of hulls produced.
void calcConvexDecomposition(unsigned int vcount,
const float *vertices,
unsigned int tcount,
const unsigned int *indices,
ConvexDecompInterface *callback,
float masterVolume,
unsigned int depth);
};
#endif

View File

@@ -1725,7 +1725,6 @@ int AssertIntact(ConvexH &convex) {
inext = estart;
}
assert(convex.edges[inext].p == convex.edges[i].p);
HalfEdge &edge = convex.edges[i];
int nb = convex.edges[i].ea;
assert(nb!=255);
if(nb==255 || nb==-1) return 0;
@@ -1852,10 +1851,6 @@ ConvexH *ConvexHCrop(ConvexH &convex,const Plane &slice)
int i;
int vertcountunder=0;
int vertcountover =0;
int edgecountunder=0;
int edgecountover =0;
int planecountunder=0;
int planecountover =0;
static Array<int> vertscoplanar; // existing vertex members of convex that are coplanar
vertscoplanar.count=0;
static Array<int> edgesplit; // existing edges that members of convex that cross the splitplane
@@ -1886,7 +1881,7 @@ ConvexH *ConvexHCrop(ConvexH &convex,const Plane &slice)
else {
assert(vertflag[i].planetest == OVER);
vertflag[i].overmap = vertcountover++;
vertflag[i].undermap = -1; // for debugging purposes
vertflag[i].undermap = 255; // for debugging purposes
}
}
int vertcountunderold = vertcountunder; // for debugging only
@@ -1897,11 +1892,9 @@ ConvexH *ConvexHCrop(ConvexH &convex,const Plane &slice)
for(int currentplane=0; currentplane<convex.facets.count; currentplane++) {
int estart =e0;
int enextface;
int enextface = 0;
int planeside = 0;
int e1 = e0+1;
int eus=-1;
int ecop=-1;
int vout=-1;
int vin =-1;
int coplanaredge = -1;
@@ -2157,8 +2150,8 @@ ConvexH *ConvexHCrop(ConvexH &convex,const Plane &slice)
static int candidateplane(Plane *planes,int planes_count,ConvexH *convex,float epsilon)
{
int p ;
REAL md;
int p = 0 ;
REAL md= 0 ;
int i;
for(i=0;i<planes_count;i++)
{
@@ -2520,7 +2513,6 @@ int calchullgen(float3 *verts,int verts_count, int vlimit)
isextreme[v]=1;
//if(v==p0 || v==p1 || v==p2 || v==p3) continue; // done these already
j=tris.count;
int newstart=j;
while(j--) {
if(!tris[j]) continue;
int3 t=*tris[j];
@@ -2619,7 +2611,7 @@ int overhull(Plane *planes,int planes_count,float3 *verts, int verts_count,int m
float3 *&verts_out, int &verts_count_out, int *&faces_out, int &faces_count_out ,float inflate)
{
int i,j;
if(verts_count <4) return NULL;
if(verts_count <4) return 0;
maxplanes = Min(maxplanes,planes_count);
float3 bmin(verts[0]),bmax(verts[0]);
for(i=0;i<verts_count;i++)
@@ -2627,7 +2619,7 @@ int overhull(Plane *planes,int planes_count,float3 *verts, int verts_count,int m
bmin = VectorMin(bmin,verts[i]);
bmax = VectorMax(bmax,verts[i]);
}
float diameter = magnitude(bmax-bmin);
// float diameter = magnitude(bmax-bmin);
// inflate *=diameter; // RELATIVE INFLATION
bmin -= float3(inflate,inflate,inflate);
bmax += float3(inflate,inflate,inflate);
@@ -2957,9 +2949,7 @@ bool HullLibrary::CleanupVertices(unsigned int svcount,
if ( svcount == 0 ) return false;
#define EPSILON 0.000001f // close enough to consider two floating point numbers to be 'the same'.
bool ret = false;
#define EPSILON 0.000001f /* close enough to consider two floating point numbers to be 'the same'. */
vcount = 0;

View File

@@ -88,7 +88,9 @@ typedef std::vector< float > FloatVector;
class InPlaceParserInterface
{
public:
virtual int ParseLine(int lineno,int argc,const char **argv) =0; // return TRUE to continue parsing, return FALSE to abort parsing process
virtual ~InPlaceParserInterface () {} ;
virtual int ParseLine(int lineno,int argc,const char **argv) =0; // return TRUE to continue parsing, return FALSE to abort parsing process
};
enum SeparatorType
@@ -157,23 +159,23 @@ public:
void SetHardSeparator(char c) // add a hard separator
{
mHard[c] = ST_HARD;
mHard[(int)c] = ST_HARD;
}
void SetHard(char c) // add a hard separator
{
mHard[c] = ST_HARD;
mHard[(int)c] = ST_HARD;
}
void SetCommentSymbol(char c) // comment character, treated as 'end of string'
{
mHard[c] = ST_EOS;
mHard[(int)c] = ST_EOS;
}
void ClearHardSeparator(char c)
{
mHard[c] = ST_DATA;
mHard[(int)c] = ST_DATA;
}
@@ -181,7 +183,7 @@ public:
bool EOS(char c)
{
if ( mHard[c] == ST_EOS )
if ( mHard[(int)c] == ST_EOS )
{
return true;
}
@@ -261,7 +263,7 @@ InPlaceParser::~InPlaceParser(void)
bool InPlaceParser::IsHard(char c)
{
return mHard[c] == ST_HARD;
return mHard[(int)c] == ST_HARD;
}
char * InPlaceParser::AddHard(int &argc,const char **argv,char *foo)
@@ -280,7 +282,7 @@ char * InPlaceParser::AddHard(int &argc,const char **argv,char *foo)
bool InPlaceParser::IsWhiteSpace(char c)
{
return mHard[c] == ST_SOFT;
return mHard[(int)c] == ST_SOFT;
}
char * InPlaceParser::SkipSpaces(char *foo)
@@ -550,10 +552,9 @@ class GeometryInterface
{
public:
virtual void NodeTriangle(const GeometryVertex *v1,const GeometryVertex *v2,const GeometryVertex *v3)
{
}
virtual void NodeTriangle(const GeometryVertex *v1,const GeometryVertex *v2,const GeometryVertex *v3) {}
virtual ~GeometryInterface () {}
};

View File

@@ -113,7 +113,6 @@ static void intersect(const float *p1,const float *p2,float *split,const float *
{
float dp1 = DistToPt(p1,plane);
float dp2 = DistToPt(p2,plane);
float dir[3];
@@ -129,7 +128,6 @@ static void intersect(const float *p1,const float *p2,float *split,const float *
split[0] = (dir[0]*t)+p1[0];
split[1] = (dir[1]*t)+p1[1];
split[2] = (dir[2]*t)+p1[2];
}
@@ -602,8 +600,6 @@ float computeConcavity(unsigned int vcount,
float bmin[3];
float bmax[3];
float diagonal = getBoundingRegion( result.mNumOutputVertices, result.mOutputVertices, sizeof(float)*3, bmin, bmax );
float dx = bmax[0] - bmin[0];
float dy = bmax[1] - bmin[1];
float dz = bmax[2] - bmin[2];
@@ -614,8 +610,6 @@ float computeConcavity(unsigned int vcount,
center.y = bmin[1] + dy*0.5f;
center.z = bmin[2] + dz*0.5f;
float boundVolume = dx*dy*dz;
volume = computeMeshVolume2( result.mOutputVertices, result.mNumFaces, result.mIndices );
#if 1

View File

@@ -43,7 +43,6 @@ float computeMeshVolume(const float *vertices,unsigned int tcount,const unsigned
{
float volume = 0;
const float *p0 = vertices;
for (unsigned int i=0; i<tcount; i++,indices+=3)
{

View File

@@ -78,7 +78,6 @@ static void intersect(const float *p1,const float *p2,float *split,const float *
{
float dp1 = DistToPt(p1,plane);
float dp2 = DistToPt(p2,plane);
float dir[3];

View File

@@ -185,9 +185,6 @@ bool computeSplitPlane(unsigned int vcount,
ConvexDecompInterface *callback,
float *plane)
{
bool cret = false;
float bmin[3] = { 1e9, 1e9, 1e9 };
float bmax[3] = { -1e9, -1e9, -1e9 };

View File

@@ -722,6 +722,7 @@ xmlSchematronFreeParserCtxt(xmlSchematronParserCtxtPtr ctxt)
*
* Add an included document
*/
#if 0
static void
xmlSchematronPushInclude(xmlSchematronParserCtxtPtr ctxt,
xmlDocPtr doc, xmlNodePtr cur)
@@ -754,6 +755,7 @@ xmlSchematronPushInclude(xmlSchematronParserCtxtPtr ctxt,
ctxt->includes[2 * ctxt->nbIncludes + 1] = (xmlNodePtr) doc;
ctxt->nbIncludes++;
}
#endif
/**
* xmlSchematronPopInclude:
@@ -996,6 +998,7 @@ xmlSchematronParsePattern(xmlSchematronParserCtxtPtr ctxt, xmlNodePtr pat)
*
* Returns the updated node pointer
*/
#if 0
static xmlNodePtr
xmlSchematronLoadInclude(xmlSchematronParserCtxtPtr ctxt, xmlNodePtr cur)
{
@@ -1051,6 +1054,7 @@ done:
xmlFree(URI);
return(ret);
}
#endif
/**
* xmlSchematronParse:

View File

@@ -327,13 +327,13 @@ static void DrawAabb(IDebugDraw* debugDrawer,const SimdVector3& from,const SimdV
CcdPhysicsEnvironment::CcdPhysicsEnvironment(Dispatcher* dispatcher,OverlappingPairCache* pairCache)
:m_scalingPropagated(false),
m_numIterations(10),
: m_numIterations(10),
m_numTimeSubSteps(1),
m_ccdMode(0),
m_solverType(-1),
m_profileTimings(0),
m_enableSatCollisionDetection(false)
m_enableSatCollisionDetection(false),
m_scalingPropagated(false)
{
for (int i=0;i<PHY_NUM_RESPONSE;i++)
@@ -383,9 +383,6 @@ void CcdPhysicsEnvironment::addCcdPhysicsController(CcdPhysicsController* ctrl)
assert(body->m_broadphaseHandle);
BroadphaseInterface* scene = GetBroadphase();
CollisionShape* shapeinterface = ctrl->GetCollisionShape();
assert(shapeinterface);
@@ -695,10 +692,6 @@ bool CcdPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
Profiler::endBlock("DispatchAllCollisionPairs");
#endif //USE_QUICKPROF
int numRigidBodies = m_controllers.size();
m_islandManager->UpdateActivationState(GetCollisionWorld(),GetCollisionWorld()->GetDispatcher());
{
@@ -1445,10 +1438,6 @@ void CcdPhysicsEnvironment::removeConstraint(int constraintId)
PHY_IPhysicsController* CcdPhysicsEnvironment::rayTest(PHY_IPhysicsController* ignoreClient, float fromX,float fromY,float fromZ, float toX,float toY,float toZ,
float& hitX,float& hitY,float& hitZ,float& normalX,float& normalY,float& normalZ)
{
float minFraction = 1.f;
SimdVector3 rayFrom(fromX,fromY,fromZ);
SimdVector3 rayTo(toX,toY,toZ);
@@ -1629,9 +1618,6 @@ void CcdPhysicsEnvironment::requestCollisionCallback(PHY_IPhysicsController* ctr
void CcdPhysicsEnvironment::CallbackTriggers()
{
CcdPhysicsController* ctrl0=0,*ctrl1=0;
if (m_triggerCallbacks[PHY_OBJECT_RESPONSE] || (m_debugDrawer && (m_debugDrawer->GetDebugMode() & IDebugDraw::DBG_DrawContactPoints)))
{
//walk over all overlapping pairs, and if one of the involved bodies is registered for trigger callback, perform callback

View File

@@ -264,3 +264,4 @@ protected:
};
#endif //CCDPHYSICSENVIRONMENT

View File

@@ -286,13 +286,13 @@ void ParallelIslandDispatcher::DispatchAllCollisionPairs(OverlappingPairCache* p
{
//m_blockedForChanges = true;
int i;
int dispatcherId = GetUniqueId();
assert(0);
/*
int dispatcherId = GetUniqueId();
int i;
for (i=0;i<numPairs;i++)
{

View File

@@ -134,15 +134,15 @@ bool ParallelPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
*/
//store constraint indices for each island
for (i=0;i<m_constraints.size();i++)
for (unsigned int ui=0;ui<m_constraints.size();ui++)
{
TypedConstraint& constraint = *m_constraints[i];
TypedConstraint& constraint = *m_constraints[ui];
if (constraint.GetRigidBodyA().m_islandTag1 > constraint.GetRigidBodyB().m_islandTag1)
{
simulationIslands[constraint.GetRigidBodyA().m_islandTag1].m_constraintIndices.push_back(i);
simulationIslands[constraint.GetRigidBodyA().m_islandTag1].m_constraintIndices.push_back(ui);
} else
{
simulationIslands[constraint.GetRigidBodyB().m_islandTag1].m_constraintIndices.push_back(i);
simulationIslands[constraint.GetRigidBodyB().m_islandTag1].m_constraintIndices.push_back(ui);
}
}
@@ -203,4 +203,4 @@ bool ParallelPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
return true;
}
}

View File

@@ -92,7 +92,7 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
overlappingPairs.resize(this->m_overlappingPairIndices.size());
//gather overlapping pair info
int i;
unsigned int i;
for (i=0;i<m_overlappingPairIndices.size();i++)
{
overlappingPairs[i] = overlappingPairBaseAddress[m_overlappingPairIndices[i]];
@@ -119,13 +119,6 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
#endif //USE_QUICKPROF
int numRigidBodies = m_controllers.size();
//contacts
#ifdef USE_QUICKPROF
Profiler::beginBlock("SolveConstraint");
@@ -407,8 +400,8 @@ void SimulationIsland::UpdateAabbs(IDebugDraw* debugDrawer,BroadphaseInterface*
SimdVector3 color (1,1,0);
class IDebugDraw* m_debugDrawer = 0;
/*
class IDebugDraw* m_debugDrawer = 0;
if (m_debugDrawer)
{
//draw aabb
@@ -466,4 +459,4 @@ void SimulationIsland::UpdateAabbs(IDebugDraw* debugDrawer,BroadphaseInterface*
}
}
}
}

View File

@@ -50,4 +50,6 @@ class SimulationIsland
void UpdateAabbs(IDebugDraw* debugDrawer,BroadphaseInterface* broadphase,float timeStep);
};
#endif //SIMULATION_ISLAND_H
#endif //SIMULATION_ISLAND_H

View File

@@ -200,4 +200,5 @@ const Matrix44 Inv(const Matrix44& src)
// Matrix66
#endif
#endif //#ifdef WIN32
#endif //#ifdef WIN32

View File

@@ -35,4 +35,5 @@ const Scalar Scalar::Consts::NegInfinity(0xff800000, true);
const Scalar Scalar::Consts::AbsMask(0x7fffffff, true);
#endif
#endif //WIN32
#endif //WIN32