diff --git a/Demos/ColladaDemo/ColladaDemo.cpp b/Demos/ColladaDemo/ColladaDemo.cpp index 79df38257..7a7736a32 100644 --- a/Demos/ColladaDemo/ColladaDemo.cpp +++ b/Demos/ColladaDemo/ColladaDemo.cpp @@ -1,1305 +1,1325 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#include "CcdPhysicsEnvironment.h" -#include "CcdPhysicsController.h" - -//#include "GL_LineSegmentShape.h" -#include "CollisionShapes/BoxShape.h" -#include "CollisionShapes/SphereShape.h" -#include "CollisionShapes/ConeShape.h" - - -#include "CollisionShapes/Simplex1to4Shape.h" -#include "CollisionShapes/EmptyShape.h" - -#include "Dynamics/RigidBody.h" -#include "CollisionDispatch/CollisionDispatcher.h" -#include "BroadphaseCollision/SimpleBroadphase.h" -#include "BroadphaseCollision/AxisSweep3.h" -#include "ConstraintSolver/Point2PointConstraint.h" -#include "ConstraintSolver/HingeConstraint.h" - -#include "quickprof.h" -#include "IDebugDraw.h" - -#include "GLDebugDrawer.h" - -#define COLLADA_PHYSICS_TEST 1 -#ifdef COLLADA_PHYSICS_TEST - -//Collada Physics test -//#define NO_LIBXML //need LIBXML, because FCDocument/FCDPhysicsRigidBody.h needs FUDaeWriter, through FCDPhysicsParameter.hpp -#include "FUtils/FUtils.h" -#include "FCDocument/FCDocument.h" -#include "FCDocument/FCDSceneNode.h" -#include "FUtils/FUFileManager.h" -#include "FUtils/FULogFile.h" -#include "FCDocument/FCDPhysicsSceneNode.h" -#include "FCDocument/FCDPhysicsModelInstance.h" -#include "FCDocument/FCDPhysicsRigidBodyInstance.h" -#include "FCDocument/FCDPhysicsRigidBody.h" -#include "FCDocument/FCDGeometryInstance.h" -#include "FCDocument/FCDGeometryMesh.h" -#include "FCDocument/FCDGeometry.h" -#include "FCDocument/FCDPhysicsAnalyticalGeometry.h" - - -//aaa - - - - - -#endif //COLLADA_PHYSICS_TEST - - - - -#include "PHY_Pro.h" -#include "BMF_Api.h" -#include //printf debugging - -float deltaTime = 1.f/60.f; -float bulletSpeed = 40.f; -bool createConstraint = true; -#ifdef WIN32 -#if _MSC_VER >= 1310 -//only use SIMD Hull code under Win32 -#define USE_HULL 1 -#include "NarrowPhaseCollision/Hull.h" -#endif //_MSC_VER -#endif //WIN32 - - -#ifdef WIN32 //needed for glut.h -#include -#endif -#include -#include "GL_ShapeDrawer.h" - -#include "GlutStuff.h" - - -extern float eye[3]; -extern int glutScreenWidth; -extern int glutScreenHeight; - - -#ifdef _DEBUG -const int numObjects = 120;//22; -#else -const int numObjects = 120; -#endif - -const int maxNumObjects = 450; - -DefaultMotionState ms[maxNumObjects]; -CcdPhysicsController* physObjects[maxNumObjects] = {0,0,0,0}; -int shapeIndex[maxNumObjects]; -CcdPhysicsEnvironment* physicsEnvironmentPtr = 0; - - -#define CUBE_HALF_EXTENTS 1 - -#define EXTRA_HEIGHT -20.f -//GL_LineSegmentShape shapeE(SimdPoint3(-50,0,0), -// SimdPoint3(50,0,0)); -static const int numShapes = 4; - -CollisionShape* shapePtr[numShapes] = -{ - ///Please don't make the box sizes larger then 1000: the collision detection will be inaccurate. - ///See http://www.continuousphysics.com/Bullet/phpBB2/viewtopic.php?t=346 - - new BoxShape (SimdVector3(450,10,450)), - new BoxShape (SimdVector3(CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS)), - new SphereShape (CUBE_HALF_EXTENTS- 0.05f), - - //new ConeShape(CUBE_HALF_EXTENTS,2.f*CUBE_HALF_EXTENTS), - //new BU_Simplex1to4(SimdPoint3(-1,-1,-1),SimdPoint3(1,-1,-1),SimdPoint3(-1,1,-1),SimdPoint3(0,0,1)), - - //new EmptyShape(), - - new BoxShape (SimdVector3(0.4,1,0.8)) - -}; - - - -//////////////////////////////////// - -#ifdef COLLADA_PHYSICS_TEST - - -bool ConvertColladaPhysicsToBulletPhysics(const FCDPhysicsSceneNode* inputNode) -{ - - assert(inputNode); - - /// FRSceneNodeList nodesToDelete; - // FRMeshPhysicsController::StartCooking(); - - FCDPhysicsModelInstanceList models = inputNode->GetInstances(); - - //Go through all of the physics models - for (FCDPhysicsModelInstanceList::iterator itM=models.begin(); itM != models.end(); itM++) - { - - FCDEntityInstanceList& instanceList = (*itM)->GetInstances(); - //create one node per physics model. This node is pretty much only a middle man, - //but better describes the structure we get from the input file - //FRSceneNode* modelNode = new FRSceneNode(); - //modelNode->SetParent(outputNode); - //outputNode->AddChild(modelNode); - //Go through all of the rigid bodies and rigid constraints in that model - - for (FCDEntityInstanceList::iterator itE=instanceList.begin(); itE!=instanceList.end(); itE++) - { - if ((*itE)->GetType() == FCDEntityInstance::PHYSICS_RIGID_CONSTRAINT) - { - //not yet, could add point to point / hinge support easily - } - else - if ((*itE)->GetType() == FCDEntityInstance::PHYSICS_RIGID_BODY) - { - - printf("PHYSICS_RIGID_BODY\n"); - - - //Create a controller per rigid-body - - //FRMeshPhysicsController* controller = new FRMeshPhysicsController(inputNode->GetGravity(), inputNode->GetTimestep()); - FCDPhysicsRigidBodyInstance* rbInstance = (FCDPhysicsRigidBodyInstance*)(*itE); - - FCDSceneNode* targetNode = rbInstance->GetTargetNode(); - - - if (!targetNode) - { - - - //DebugOut("FCTranslator: No target node defined in rigid body instance"); - - //SAFE_DELETE(controller); - - continue; - } - - - //Transfer all the transforms in n into cNode, and bake - //at the same time the scalings. It is necessary to re-translate the - //transforms as they will get deleted when we delete the old node. - //A better way to do this would be to steal the transforms from the old - //nodes, and make sure they're not deleted later, but this is impractical - //right now as we would also have to migrate all the animation curves. - - - //FRTScaleList scaleTransforms; - - uint32 numTransforms = targetNode->GetTransformCount(); - - for (uint32 i=0; iGetTransforms()[i]); - } - - //Then affect all of its geometry instances. - //Collect all the entities inside the entity vector and inside the children nodes -/* - FREntityList childEntities = n->GetEntities(); - FRSceneNodeList childrenToParse = n->GetChildren(); - - while (!childrenToParse.empty()) - { - FRSceneNode* child = *childrenToParse.begin(); - const FREntityList& e = child->GetEntities(); - //add the entities of that child - childEntities.insert(childEntities.end(), e.begin(), e.end()); - //queue the grand-children nodes - childrenToParse.insert(childrenToParse.end(), child->GetChildren().begin(), child->GetChildren().end()); - childrenToParse.erase(childrenToParse.begin()); - - } -*/ - //now check which ones are geometry mesh (right now an entity is only derived by mesh - //but do this to avoid problems in the future) -/* - for (FREntityList::iterator itT = childEntities.begin(); itT != childEntities.end(); itT++) - { - - if ((*itT)->GetType() == FREntity::MESH || (*itT)->GetType() == FREntity::MESH_CONTROLLER) - - { - - FRMesh* cMesh = (FRMesh*)*itT; - - //while we're here, bake the scaling transforms into the meshes - - BakeScalingIntoMesh(cMesh, scaleTransforms); - - controller->AddBindMesh((FRMesh*)*itT); - - } - - } -*/ - - - ///////////////////////////////////////////////////////////////////// - //We're done with the targets. Now take care of the physics shapes. - FCDPhysicsRigidBody* rigidBody = rbInstance->FlattenRigidBody(); - FCDPhysicsMaterial* mat = rigidBody->GetPhysicsMaterial(); - FCDPhysicsShapeList shapes = rigidBody->GetPhysicsShapeList(); - for (uint32 i=0; iGetType();// - //controller->SetDensity(OldShape->GetDensity()); - - - if (OldShape->GetGeometryInstance()) - { - - FCDGeometry* geoTemp = (FCDGeometry*)(OldShape->GetGeometryInstance()->GetEntity()); - - const FCDGeometryMesh* colladaMesh = geoTemp->GetMesh(); - - - - //FRMesh* cMesh = ToFREntityGeometry(geoTemp); - //BakeScalingIntoMesh(cMesh, scaleTransforms); - - for (uint32 j=0; jGetPolygonsCount(); j++) - { - - /* - FRMeshPhysicsShape* NewShape = new FRMeshPhysicsShape(controller); - - if (!NewShape->CreateTriangleMesh(cMesh, j, true)) - - { - - SAFE_DELETE(NewShape); - - continue; - - } - if (mat) - { - NewShape->SetMaterial(mat->GetStaticFriction(), mat->GetDynamicFriction(), mat->GetRestitution()); - //FIXME - //NewShape->material->setFrictionCombineMode(); - //NewShape->material->setSpring(); - } - - controller->AddShape(NewShape); - - */ - } - - - - } - - else - - { - - //FRMeshPhysicsShape* NewShape = new FRMeshPhysicsShape(controller); - - FCDPhysicsAnalyticalGeometry* analGeom = OldShape->GetAnalyticalGeometry(); - - //increse the following value for nicer shapes with more vertices - - uint16 superEllipsoidSubdivisionLevel = 2; - - if (!analGeom) - - continue; - - switch (analGeom->GetGeomType()) - - { - - case FCDPhysicsAnalyticalGeometry::BOX: - - { - - FCDPASBox* box = (FCDPASBox*)analGeom; - - break; - - } - - case FCDPhysicsAnalyticalGeometry::PLANE: - - { - - FCDPASPlane* plane = (FCDPASPlane*)analGeom; - - break; - - } - - case FCDPhysicsAnalyticalGeometry::SPHERE: - - { - - FCDPASSphere* sphere = (FCDPASSphere*)analGeom; - - break; - - } - - case FCDPhysicsAnalyticalGeometry::CYLINDER: - - { - - //FIXME: only using the first radius of the cylinder - - FCDPASCylinder* cylinder = (FCDPASCylinder*)analGeom; - - - break; - - } - - case FCDPhysicsAnalyticalGeometry::CAPSULE: - - { - - //FIXME: only using the first radius of the capsule - - FCDPASCapsule* capsule = (FCDPASCapsule*)analGeom; - - - break; - - } - - case FCDPhysicsAnalyticalGeometry::TAPERED_CAPSULE: - - { - - //FIXME: only using the first radius of the capsule - - FCDPASTaperedCapsule* tcapsule = (FCDPASTaperedCapsule*)analGeom; - - break; - - } - - case FCDPhysicsAnalyticalGeometry::TAPERED_CYLINDER: - - { - - //FIXME: only using the first radius of the cylinder - - FCDPASTaperedCylinder* tcylinder = (FCDPASTaperedCylinder*)analGeom; - - break; - - } - - default: - - { - - break; - - } - - } - - //controller->AddShape(NewShape); - } - - } - - FCDPhysicsParameter* dyn = (FCDPhysicsParameter*)rigidBody->FindParameterByReference(DAE_DYNAMIC_ELEMENT); - - if (dyn) - { - bool* mydyn = dyn->GetValue(); - printf("mydyn %i\n",*mydyn); - } - - FCDPhysicsParameter* mass = (FCDPhysicsParameter*)rigidBody->FindParameterByReference(DAE_MASS_ELEMENT); - - if (mass) - { - float* mymass = mass->GetValue(); - printf("RB mass:%f\n",*mymass); - } - - FCDPhysicsParameter* inertia = (FCDPhysicsParameter*)rigidBody->FindParameterByReference(DAE_INERTIA_ELEMENT); - - if (inertia) - { - inertia->GetValue(); - } - - FCDPhysicsParameter* velocity = (FCDPhysicsParameter*)rigidBody->FindParameterByReference(DAE_VELOCITY_ELEMENT); - - if (velocity) - { - velocity->GetValue(); - } - - FCDPhysicsParameter* angularVelocity = (FCDPhysicsParameter*)rigidBody->FindParameterByReference(DAE_ANGULAR_VELOCITY_ELEMENT); - - if (angularVelocity) - { - angularVelocity->GetValue(); - } - - //controller->SetGlobalPose(n->CalculateWorldTransformation());//?? - - //SAFE_DELETE(rigidBody); - - } - - } - - } - - return true; -} - - - -#endif //COLLADA_PHYSICS_TEST - - -//////////////////////////////////// - - - -GLDebugDrawer debugDrawer; - -int main(int argc,char** argv) -{ - -#ifdef COLLADA_PHYSICS_TEST - char* filename = "analyticalGeomPhysicsTest.dae";//ColladaPhysics.dae"; - FCDocument* document = new FCDocument(); - FUStatus status = document->LoadFromFile(filename); - bool success = status.IsSuccessful(); - printf ("Collada import %i\n",success); - - if (success) - { - const FCDPhysicsSceneNode* physicsSceneRoot = document->GetPhysicsSceneRoot(); - if (ConvertColladaPhysicsToBulletPhysics( physicsSceneRoot )) - { - printf("ConvertColladaPhysicsToBulletPhysics successfull\n"); - } else - { - printf("ConvertColladaPhysicsToBulletPhysics failed\n"); - } - - - } -#endif //COLLADA_PHYSICS_TEST - - CollisionDispatcher* dispatcher = new CollisionDispatcher(); - - - SimdVector3 worldAabbMin(-10000,-10000,-10000); - SimdVector3 worldAabbMax(10000,10000,10000); - - BroadphaseInterface* broadphase = new AxisSweep3(worldAabbMin,worldAabbMax); - //BroadphaseInterface* broadphase = new SimpleBroadphase(); - - physicsEnvironmentPtr = new CcdPhysicsEnvironment(dispatcher,broadphase); - physicsEnvironmentPtr->setDeactivationTime(2.f); - - physicsEnvironmentPtr->setGravity(0,-10,0); - PHY_ShapeProps shapeProps; - - shapeProps.m_do_anisotropic = false; - shapeProps.m_do_fh = false; - shapeProps.m_do_rot_fh = false; - shapeProps.m_friction_scaling[0] = 1.; - shapeProps.m_friction_scaling[1] = 1.; - shapeProps.m_friction_scaling[2] = 1.; - - shapeProps.m_inertia = 1.f; - shapeProps.m_lin_drag = 0.2f; - shapeProps.m_ang_drag = 0.1f; - shapeProps.m_mass = 10.0f; - - PHY_MaterialProps materialProps; - materialProps.m_friction = 10.5f; - materialProps.m_restitution = 0.0f; - - CcdConstructionInfo ccdObjectCi; - ccdObjectCi.m_friction = 0.5f; - - ccdObjectCi.m_linearDamping = shapeProps.m_lin_drag; - ccdObjectCi.m_angularDamping = shapeProps.m_ang_drag; - - SimdTransform tr; - tr.setIdentity(); - - int i; - for (i=0;i0) - { - shapeIndex[i] = 1;//sphere - } - else - shapeIndex[i] = 0; - } - - - - - for (i=0;iSetMargin(0.05f); - - - - bool isDyna = i>0; - //if (i==1) - // isDyna=false; - - if (0)//i==1) - { - SimdQuaternion orn(0,0,0.1*SIMD_HALF_PI); - ms[i].setWorldOrientation(orn.x(),orn.y(),orn.z(),orn[3]); - } - - - if (i>0) - { - - switch (i) - { - case 1: - { - ms[i].setWorldPosition(0,10,0); - //for testing, rotate the ground cube so the stack has to recover a bit - - break; - } - case 2: - { - ms[i].setWorldPosition(0,8,2); - break; - } - default: - ms[i].setWorldPosition(0,i*CUBE_HALF_EXTENTS*2 - CUBE_HALF_EXTENTS,0); - } - - float quatIma0,quatIma1,quatIma2,quatReal; - SimdQuaternion quat; - SimdVector3 axis(0,0,1); - SimdScalar angle=0.5f; - - quat.setRotation(axis,angle); - - ms[i].setWorldOrientation(quat.getX(),quat.getY(),quat.getZ(),quat[3]); - - - - } else - { - ms[i].setWorldPosition(0,-10+EXTRA_HEIGHT,0); - - } - - ccdObjectCi.m_MotionState = &ms[i]; - ccdObjectCi.m_gravity = SimdVector3(0,0,0); - ccdObjectCi.m_localInertiaTensor =SimdVector3(0,0,0); - if (!isDyna) - { - shapeProps.m_mass = 0.f; - ccdObjectCi.m_mass = shapeProps.m_mass; - ccdObjectCi.m_collisionFlags = CollisionObject::isStatic; - } - else - { - shapeProps.m_mass = 1.f; - ccdObjectCi.m_mass = shapeProps.m_mass; - ccdObjectCi.m_collisionFlags = 0; - } - - - SimdVector3 localInertia; - if (shapePtr[shapeIndex[i]]->GetShapeType() == EMPTY_SHAPE_PROXYTYPE) - { - //take inertia from first shape - shapePtr[1]->CalculateLocalInertia(shapeProps.m_mass,localInertia); - } else - { - shapePtr[shapeIndex[i]]->CalculateLocalInertia(shapeProps.m_mass,localInertia); - } - ccdObjectCi.m_localInertiaTensor = localInertia; - - ccdObjectCi.m_collisionShape = shapePtr[shapeIndex[i]]; - - - physObjects[i]= new CcdPhysicsController( ccdObjectCi); - - // Only do CCD if motion in one timestep (1.f/60.f) exceeds CUBE_HALF_EXTENTS - physObjects[i]->GetRigidBody()->m_ccdSquareMotionTreshold = CUBE_HALF_EXTENTS; - - //Experimental: better estimation of CCD Time of Impact: - //physObjects[i]->GetRigidBody()->m_ccdSweptShereRadius = 0.5*CUBE_HALF_EXTENTS; - - physicsEnvironmentPtr->addCcdPhysicsController( physObjects[i]); - - if (i==1) - { - //physObjects[i]->SetAngularVelocity(0,0,-2,true); - } - - physicsEnvironmentPtr->setDebugDrawer(&debugDrawer); - - } - - - //create a constraint - if (createConstraint) - { - //physObjects[i]->SetAngularVelocity(0,0,-2,true); - int constraintId; - - float pivotX=CUBE_HALF_EXTENTS, - pivotY=-CUBE_HALF_EXTENTS, - pivotZ=CUBE_HALF_EXTENTS; - - float axisX=1,axisY=0,axisZ=0; - - - - HingeConstraint* hinge = 0; - - SimdVector3 pivotInA(CUBE_HALF_EXTENTS,-CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS); - SimdVector3 pivotInB(-CUBE_HALF_EXTENTS,-CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS); - SimdVector3 axisInA(0,1,0); - SimdVector3 axisInB(0,-1,0); - - RigidBody* rb0 = physObjects[1]->GetRigidBody(); - RigidBody* rb1 = physObjects[2]->GetRigidBody(); - - hinge = new HingeConstraint( - *rb0, - *rb1,pivotInA,pivotInB,axisInA,axisInB); - - physicsEnvironmentPtr->m_constraints.push_back(hinge); - - hinge->SetUserConstraintId(100); - hinge->SetUserConstraintType(PHY_LINEHINGE_CONSTRAINT); - - } - - - - - clientResetScene(); - - setCameraDistance(26.f); - - return glutmain(argc, argv,640,480,"Bullet Physics Demo. http://www.continuousphysics.com/Bullet/phpBB2/"); -} - -//to be implemented by the demo -void renderme() -{ - debugDrawer.SetDebugMode(getDebugMode()); - - //render the hinge axis - if (createConstraint) - { - SimdVector3 color(1,0,0); - SimdVector3 dirLocal(0,1,0); - SimdVector3 pivotInA(CUBE_HALF_EXTENTS,-CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS); - SimdVector3 pivotInB(-CUBE_HALF_EXTENTS,-CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS); - SimdVector3 from = physObjects[1]->GetRigidBody()->getCenterOfMassTransform()(pivotInA); - SimdVector3 fromB = physObjects[2]->GetRigidBody()->getCenterOfMassTransform()(pivotInB); - SimdVector3 dirWorldA = physObjects[1]->GetRigidBody()->getCenterOfMassTransform().getBasis() * dirLocal ; - SimdVector3 dirWorldB = physObjects[2]->GetRigidBody()->getCenterOfMassTransform().getBasis() * dirLocal ; - debugDrawer.DrawLine(from,from+dirWorldA,color); - debugDrawer.DrawLine(fromB,fromB+dirWorldB,color); - } - - float m[16]; - int i; - - - if (getDebugMode() & IDebugDraw::DBG_DisableBulletLCP) - { - //don't use Bullet, use quickstep - physicsEnvironmentPtr->setSolverType(0); - } else - { - //Bullet LCP solver - physicsEnvironmentPtr->setSolverType(1); - } - - if (getDebugMode() & IDebugDraw::DBG_EnableCCD) - { - physicsEnvironmentPtr->setCcdMode(3); - } else - { - physicsEnvironmentPtr->setCcdMode(0); - } - - - bool isSatEnabled = (getDebugMode() & IDebugDraw::DBG_EnableSatComparison); - - physicsEnvironmentPtr->EnableSatCollisionDetection(isSatEnabled); - - -#ifdef USE_HULL - //some testing code for SAT - if (isSatEnabled) - { - for (int s=0;sIsPolyhedral()) - { - PolyhedralConvexShape* polyhedron = static_cast(shape); - if (!polyhedron->m_optionalHull) - { - //first convert vertices in 'Point3' format - int numPoints = polyhedron->GetNumVertices(); - Point3* points = new Point3[numPoints+1]; - //first 4 points should not be co-planar, so add central point to satisfy MakeHull - points[0] = Point3(0.f,0.f,0.f); - - SimdVector3 vertex; - for (int p=0;pGetVertex(p,vertex); - points[p+1] = Point3(vertex.getX(),vertex.getY(),vertex.getZ()); - } - - Hull* hull = Hull::MakeHull(numPoints+1,points); - polyhedron->m_optionalHull = hull; - } - - } - } - - } -#endif //USE_HULL - - - for (i=0;iGetRigidBody()->GetActivationState() == 1) //active - { - if (i & 1) - { - wireColor += SimdVector3 (1.f,0.f,0.f); - } else - { - wireColor += SimdVector3 (.5f,0.f,0.f); - } - } - if (physObjects[i]->GetRigidBody()->GetActivationState() == 2) //ISLAND_SLEEPING - { - if (i & 1) - { - wireColor += SimdVector3 (0.f,1.f, 0.f); - } else - { - wireColor += SimdVector3 (0.f,0.5f,0.f); - } - } - - char extraDebug[125]; - sprintf(extraDebug,"islId, Body=%i , %i",physObjects[i]->GetRigidBody()->m_islandTag1,physObjects[i]->GetRigidBody()->m_debugBodyId); - physObjects[i]->GetRigidBody()->GetCollisionShape()->SetExtraDebugInfo(extraDebug); - GL_ShapeDrawer::DrawOpenGL(m,physObjects[i]->GetRigidBody()->GetCollisionShape(),wireColor,getDebugMode()); - - ///this block is just experimental code to show some internal issues with replacing shapes on the fly. - if (getDebugMode()!=0 && (i>0)) - { - if (physObjects[i]->GetRigidBody()->GetCollisionShape()->GetShapeType() == EMPTY_SHAPE_PROXYTYPE) - { - physObjects[i]->GetRigidBody()->SetCollisionShape(shapePtr[1]); - - //remove the persistent collision pairs that were created based on the previous shape - - BroadphaseProxy* bpproxy = physObjects[i]->GetRigidBody()->m_broadphaseHandle; - - physicsEnvironmentPtr->GetBroadphase()->CleanProxyFromPairs(bpproxy); - - SimdVector3 newinertia; - SimdScalar newmass = 10.f; - physObjects[i]->GetRigidBody()->GetCollisionShape()->CalculateLocalInertia(newmass,newinertia); - physObjects[i]->GetRigidBody()->setMassProps(newmass,newinertia); - physObjects[i]->GetRigidBody()->updateInertiaTensor(); - - } - - } - - - } - - if (!(getDebugMode() & IDebugDraw::DBG_NoHelpText)) - { - - float xOffset = 10.f; - float yStart = 20.f; - - float yIncr = -2.f; - - char buf[124]; - - glColor3f(0, 0, 0); - -#ifdef USE_QUICKPROF - - - if ( getDebugMode() & IDebugDraw::DBG_ProfileTimings) - { - static int counter = 0; - counter++; - std::map::iterator iter; - for (iter = Profiler::mProfileBlocks.begin(); iter != Profiler::mProfileBlocks.end(); ++iter) - { - char blockTime[128]; - sprintf(blockTime, "%s: %lf",&((*iter).first[0]),Profiler::getBlockTime((*iter).first, Profiler::BLOCK_CYCLE_SECONDS));//BLOCK_TOTAL_PERCENT)); - glRasterPos3f(xOffset,yStart,0); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),blockTime); - yStart += yIncr; - - } - } -#endif //USE_QUICKPROF - //profiling << Profiler::createStatsString(Profiler::BLOCK_TOTAL_PERCENT); - //<< std::endl; - - - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"mouse to interact"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"space to reset"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"cursor keys and z,x to navigate"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"i to toggle simulation, s single step"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"q to quit"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"d to toggle deactivation"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"a to draw temporal AABBs"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"h to toggle help text"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - bool useBulletLCP = !(getDebugMode() & IDebugDraw::DBG_DisableBulletLCP); - - bool useCCD = (getDebugMode() & IDebugDraw::DBG_EnableCCD); - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"m Bullet GJK = %i",!isSatEnabled); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"n Bullet LCP = %i",useBulletLCP); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"1 CCD mode (adhoc) = %i",useCCD); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"+- shooting speed = %10.2f",bulletSpeed); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - } - -} - -void clientMoveAndDisplay() -{ - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - - - - physicsEnvironmentPtr->proceedDeltaTime(0.f,deltaTime); - - renderme(); - - glFlush(); - glutSwapBuffers(); - -} - - - -void clientDisplay(void) { - - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - - - physicsEnvironmentPtr->UpdateAabbs(deltaTime); - - renderme(); - - - glFlush(); - glutSwapBuffers(); -} - - - -///make this positive to show stack falling from a distance -///this shows the penalty tresholds in action, springy/spungy look - -void clientResetScene() -{ - - int i; - for (i=0;i0) - { - - if ((getDebugMode() & IDebugDraw::DBG_NoHelpText)) - { - if (physObjects[i]->GetRigidBody()->GetCollisionShape()->GetShapeType() == BOX_SHAPE_PROXYTYPE) - { - physObjects[i]->GetRigidBody()->SetCollisionShape(shapePtr[2]); - } else - { - physObjects[i]->GetRigidBody()->SetCollisionShape(shapePtr[1]); - } - - BroadphaseProxy* bpproxy = physObjects[i]->GetRigidBody()->m_broadphaseHandle; - physicsEnvironmentPtr->GetBroadphase()->CleanProxyFromPairs(bpproxy); - } - - //stack them - int colsize = 10; - int row = (i*CUBE_HALF_EXTENTS*2)/(colsize*2*CUBE_HALF_EXTENTS); - int row2 = row; - int col = (i)%(colsize)-colsize/2; - - - if (col>3) - { - col=11; - row2 |=1; - } - physObjects[i]->setPosition(col*2*CUBE_HALF_EXTENTS + (row2%2)*CUBE_HALF_EXTENTS, - row*2*CUBE_HALF_EXTENTS+CUBE_HALF_EXTENTS+EXTRA_HEIGHT,0); - physObjects[i]->setOrientation(0,0,0,1); - physObjects[i]->SetLinearVelocity(0,0,0,false); - physObjects[i]->SetAngularVelocity(0,0,0,false); - } - } -} - - - -void shootBox(const SimdVector3& destination) -{ - int i = numObjects-1; - - - - SimdVector3 linVel(destination[0]-eye[0],destination[1]-eye[1],destination[2]-eye[2]); - linVel.normalize(); - linVel*=bulletSpeed; - - physObjects[i]->setPosition(eye[0],eye[1],eye[2]); - physObjects[i]->setOrientation(0,0,0,1); - physObjects[i]->SetLinearVelocity(linVel[0],linVel[1],linVel[2],false); - physObjects[i]->SetAngularVelocity(0,0,0,false); -} - -void clientKeyboard(unsigned char key, int x, int y) -{ - - if (key == '.') - { - shootBox(SimdVector3(0,0,0)); - } - - if (key == '+') - { - bulletSpeed += 10.f; - } - if (key == '-') - { - bulletSpeed -= 10.f; - } - - defaultKeyboard(key, x, y); -} - -int gPickingConstraintId = 0; -SimdVector3 gOldPickingPos; -float gOldPickingDist = 0.f; -RigidBody* pickedBody = 0;//for deactivation state - - -SimdVector3 GetRayTo(int x,int y) -{ - float top = 1.f; - float bottom = -1.f; - float nearPlane = 1.f; - float tanFov = (top-bottom)*0.5f / nearPlane; - float fov = 2.0 * atanf (tanFov); - - SimdVector3 rayFrom(eye[0],eye[1],eye[2]); - SimdVector3 rayForward = -rayFrom; - rayForward.normalize(); - float farPlane = 600.f; - rayForward*= farPlane; - - SimdVector3 rightOffset; - SimdVector3 vertical(0.f,1.f,0.f); - SimdVector3 hor; - hor = rayForward.cross(vertical); - hor.normalize(); - vertical = hor.cross(rayForward); - vertical.normalize(); - - float tanfov = tanf(0.5f*fov); - hor *= 2.f * farPlane * tanfov; - vertical *= 2.f * farPlane * tanfov; - SimdVector3 rayToCenter = rayFrom + rayForward; - SimdVector3 dHor = hor * 1.f/float(glutScreenWidth); - SimdVector3 dVert = vertical * 1.f/float(glutScreenHeight); - SimdVector3 rayTo = rayToCenter - 0.5f * hor + 0.5f * vertical; - rayTo += x * dHor; - rayTo -= y * dVert; - return rayTo; -} -void clientMouseFunc(int button, int state, int x, int y) -{ - //printf("button %i, state %i, x=%i,y=%i\n",button,state,x,y); - //button 0, state 0 means left mouse down - - SimdVector3 rayTo = GetRayTo(x,y); - - switch (button) - { - case 2: - { - if (state==0) - { - shootBox(rayTo); - } - break; - }; - case 1: - { - if (state==0) - { - //apply an impulse - if (physicsEnvironmentPtr) - { - float hit[3]; - float normal[3]; - PHY_IPhysicsController* hitObj = physicsEnvironmentPtr->rayTest(0,eye[0],eye[1],eye[2],rayTo.getX(),rayTo.getY(),rayTo.getZ(),hit[0],hit[1],hit[2],normal[0],normal[1],normal[2]); - if (hitObj) - { - CcdPhysicsController* physCtrl = static_cast(hitObj); - RigidBody* body = physCtrl->GetRigidBody(); - if (body) - { - body->SetActivationState(ACTIVE_TAG); - SimdVector3 impulse = rayTo; - impulse.normalize(); - float impulseStrength = 10.f; - impulse *= impulseStrength; - SimdVector3 relPos( - hit[0] - body->getCenterOfMassPosition().getX(), - hit[1] - body->getCenterOfMassPosition().getY(), - hit[2] - body->getCenterOfMassPosition().getZ()); - - body->applyImpulse(impulse,relPos); - } - - } - - } - - } else - { - - } - break; - } - case 0: - { - if (state==0) - { - //add a point to point constraint for picking - if (physicsEnvironmentPtr) - { - float hit[3]; - float normal[3]; - PHY_IPhysicsController* hitObj = physicsEnvironmentPtr->rayTest(0,eye[0],eye[1],eye[2],rayTo.getX(),rayTo.getY(),rayTo.getZ(),hit[0],hit[1],hit[2],normal[0],normal[1],normal[2]); - if (hitObj) - { - - CcdPhysicsController* physCtrl = static_cast(hitObj); - RigidBody* body = physCtrl->GetRigidBody(); - - if (body) - { - pickedBody = body; - pickedBody->SetActivationState(DISABLE_DEACTIVATION); - - SimdVector3 pickPos(hit[0],hit[1],hit[2]); - - SimdVector3 localPivot = body->getCenterOfMassTransform().inverse() * pickPos; - - gPickingConstraintId = physicsEnvironmentPtr->createConstraint(physCtrl,0,PHY_POINT2POINT_CONSTRAINT, - localPivot.getX(), - localPivot.getY(), - localPivot.getZ(), - 0,0,0); - //printf("created constraint %i",gPickingConstraintId); - - //save mouse position for dragging - gOldPickingPos = rayTo; - - - SimdVector3 eyePos(eye[0],eye[1],eye[2]); - - gOldPickingDist = (pickPos-eyePos).length(); - - Point2PointConstraint* p2p = static_cast(physicsEnvironmentPtr->getConstraintById(gPickingConstraintId)); - if (p2p) - { - //very weak constraint for picking - p2p->m_setting.m_tau = 0.1f; - } - } - } - } - } else - { - if (gPickingConstraintId && physicsEnvironmentPtr) - { - physicsEnvironmentPtr->removeConstraint(gPickingConstraintId); - //printf("removed constraint %i",gPickingConstraintId); - gPickingConstraintId = 0; - pickedBody->ForceActivationState(ACTIVE_TAG); - pickedBody->m_deactivationTime = 0.f; - pickedBody = 0; - - - } - } - - break; - - } - default: - { - } - } - -} - -void clientMotionFunc(int x,int y) -{ - - if (gPickingConstraintId && physicsEnvironmentPtr) - { - - //move the constraint pivot - - Point2PointConstraint* p2p = static_cast(physicsEnvironmentPtr->getConstraintById(gPickingConstraintId)); - if (p2p) - { - //keep it at the same picking distance - - SimdVector3 newRayTo = GetRayTo(x,y); - SimdVector3 eyePos(eye[0],eye[1],eye[2]); - SimdVector3 dir = newRayTo-eyePos; - dir.normalize(); - dir *= gOldPickingDist; - - SimdVector3 newPos = eyePos + dir; - p2p->SetPivotB(newPos); - } - - } -} +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + +#include "CcdPhysicsEnvironment.h" +#include "CcdPhysicsController.h" + +//#include "GL_LineSegmentShape.h" +#include "CollisionShapes/BoxShape.h" +#include "CollisionShapes/SphereShape.h" +#include "CollisionShapes/ConeShape.h" + +#include "CollisionShapes/ConvexHullShape.h" +#include "CollisionShapes/TriangleMesh.h" +#include "CollisionShapes/ConvexTriangleMeshShape.h" +#include "CollisionShapes/TriangleMeshShape.h" + + + + +#include "CollisionShapes/Simplex1to4Shape.h" +#include "CollisionShapes/EmptyShape.h" + +#include "Dynamics/RigidBody.h" +#include "CollisionDispatch/CollisionDispatcher.h" +#include "BroadphaseCollision/SimpleBroadphase.h" +#include "BroadphaseCollision/AxisSweep3.h" +#include "ConstraintSolver/Point2PointConstraint.h" +#include "ConstraintSolver/HingeConstraint.h" + +#include "quickprof.h" +#include "IDebugDraw.h" + +#include "GLDebugDrawer.h" + + +//Collada Physics test +//#define NO_LIBXML //need LIBXML, because FCDocument/FCDPhysicsRigidBody.h needs FUDaeWriter, through FCDPhysicsParameter.hpp +#include "FUtils/FUtils.h" +#include "FCDocument/FCDocument.h" +#include "FCDocument/FCDSceneNode.h" +#include "FUtils/FUFileManager.h" +#include "FUtils/FULogFile.h" +#include "FCDocument/FCDPhysicsSceneNode.h" +#include "FCDocument/FCDPhysicsModelInstance.h" +#include "FCDocument/FCDPhysicsRigidBodyInstance.h" +#include "FCDocument/FCDPhysicsRigidBody.h" +#include "FCDocument/FCDGeometryInstance.h" +#include "FCDocument/FCDGeometrySource.h" +#include "FCDocument/FCDGeometryMesh.h" + +#include "FCDocument/FCDGeometryPolygons.h" + + +#include "FCDocument/FCDGeometry.h" +#include "FCDocument/FCDPhysicsAnalyticalGeometry.h" + + +//aaa + + + + + + + + + +#include "PHY_Pro.h" +#include "BMF_Api.h" +#include //printf debugging + +float deltaTime = 1.f/60.f; +float bulletSpeed = 40.f; + +#ifdef WIN32 +#if _MSC_VER >= 1310 +//only use SIMD Hull code under Win32 +#define USE_HULL 1 +#include "NarrowPhaseCollision/Hull.h" +#endif //_MSC_VER +#endif //WIN32 + + +#ifdef WIN32 //needed for glut.h +#include +#endif +#include +#include "GL_ShapeDrawer.h" + +#include "GlutStuff.h" + + +extern float eye[3]; +extern int glutScreenWidth; +extern int glutScreenHeight; + + + +int numObjects = 0; + +const int maxNumObjects = 450; + +DefaultMotionState ms[maxNumObjects]; +CcdPhysicsController* physObjects[maxNumObjects] = {0,0,0,0}; + +CcdPhysicsEnvironment* physicsEnvironmentPtr = 0; + + +#define CUBE_HALF_EXTENTS 1 +#define EXTRA_HEIGHT -20.f + + +CollisionShape* gShapePtr[maxNumObjects];//1 rigidbody has 1 shape (no re-use of shapes) + +//////////////////////////////////// + +///Very basic import +void CreatePhysicsObject(bool isDynamic, float mass, const SimdTransform& startTransform,CollisionShape* shape) +{ + + PHY_ShapeProps shapeProps; + + shapeProps.m_do_anisotropic = false; + shapeProps.m_do_fh = false; + shapeProps.m_do_rot_fh = false; + shapeProps.m_friction_scaling[0] = 1.; + shapeProps.m_friction_scaling[1] = 1.; + shapeProps.m_friction_scaling[2] = 1.; + + shapeProps.m_inertia = 1.f; + shapeProps.m_lin_drag = 0.2f; + shapeProps.m_ang_drag = 0.1f; + shapeProps.m_mass = 10.0f; + + PHY_MaterialProps materialProps; + materialProps.m_friction = 10.5f; + materialProps.m_restitution = 0.0f; + + CcdConstructionInfo ccdObjectCi; + ccdObjectCi.m_friction = 0.5f; + + ccdObjectCi.m_linearDamping = shapeProps.m_lin_drag; + ccdObjectCi.m_angularDamping = shapeProps.m_ang_drag; + + SimdTransform tr; + tr.setIdentity(); + + int i = numObjects; + { + gShapePtr[i] = shape; + + shapeProps.m_shape = gShapePtr[i]; + shapeProps.m_shape->SetMargin(0.05f); + + SimdQuaternion orn = startTransform.getRotation(); + + + ms[i].setWorldOrientation(orn[0],orn[1],orn[2],orn[3]); + ms[i].setWorldPosition(startTransform.getOrigin().getX(),startTransform.getOrigin().getY(),startTransform.getOrigin().getZ()); + + ccdObjectCi.m_MotionState = &ms[i]; + ccdObjectCi.m_gravity = SimdVector3(0,0,0); + ccdObjectCi.m_localInertiaTensor =SimdVector3(0,0,0); + if (!isDynamic) + { + shapeProps.m_mass = 0.f; + ccdObjectCi.m_mass = shapeProps.m_mass; + ccdObjectCi.m_collisionFlags = CollisionObject::isStatic; + } + else + { + shapeProps.m_mass = mass; + ccdObjectCi.m_mass = shapeProps.m_mass; + ccdObjectCi.m_collisionFlags = 0; + } + + + SimdVector3 localInertia(0.f,0.f,0.f); + + if (isDynamic) + { + gShapePtr[i]->CalculateLocalInertia(shapeProps.m_mass,localInertia); + } + + ccdObjectCi.m_localInertiaTensor = localInertia; + ccdObjectCi.m_collisionShape = gShapePtr[i]; + + + physObjects[i]= new CcdPhysicsController( ccdObjectCi); + + // Only do CCD if motion in one timestep (1.f/60.f) exceeds CUBE_HALF_EXTENTS + physObjects[i]->GetRigidBody()->m_ccdSquareMotionTreshold = 0.f; + + //Experimental: better estimation of CCD Time of Impact: + //physObjects[i]->GetRigidBody()->m_ccdSweptShereRadius = 0.5*CUBE_HALF_EXTENTS; + + physicsEnvironmentPtr->addCcdPhysicsController( physObjects[i]); + + } + + numObjects++; + +} + + + + +bool ConvertColladaPhysicsToBulletPhysics(const FCDPhysicsSceneNode* inputNode) +{ + + assert(inputNode); + + /// FRSceneNodeList nodesToDelete; + // FRMeshPhysicsController::StartCooking(); + + FCDPhysicsModelInstanceList models = inputNode->GetInstances(); + + //Go through all of the physics models + for (FCDPhysicsModelInstanceList::iterator itM=models.begin(); itM != models.end(); itM++) + { + + FCDEntityInstanceList& instanceList = (*itM)->GetInstances(); + //create one node per physics model. This node is pretty much only a middle man, + //but better describes the structure we get from the input file + //FRSceneNode* modelNode = new FRSceneNode(); + //modelNode->SetParent(outputNode); + //outputNode->AddChild(modelNode); + //Go through all of the rigid bodies and rigid constraints in that model + + for (FCDEntityInstanceList::iterator itE=instanceList.begin(); itE!=instanceList.end(); itE++) + { + if ((*itE)->GetType() == FCDEntityInstance::PHYSICS_RIGID_CONSTRAINT) + { + //not yet, could add point to point / hinge support easily + } + else + if ((*itE)->GetType() == FCDEntityInstance::PHYSICS_RIGID_BODY) + { + + printf("PHYSICS_RIGID_BODY\n"); + + + //Create a controller per rigid-body + + physicsEnvironmentPtr->setGravity(inputNode->GetGravity().x,inputNode->GetGravity().y,inputNode->GetGravity().z); + //FRMeshPhysicsController* controller = new FRMeshPhysicsController(inputNode->GetGravity(), inputNode->GetTimestep()); + FCDPhysicsRigidBodyInstance* rbInstance = (FCDPhysicsRigidBodyInstance*)(*itE); + + FCDSceneNode* targetNode = rbInstance->GetTargetNode(); + + + if (!targetNode) + { + + + //DebugOut("FCTranslator: No target node defined in rigid body instance"); + + //SAFE_DELETE(controller); + + continue; + } + + + //Transfer all the transforms in n into cNode, and bake + //at the same time the scalings. It is necessary to re-translate the + //transforms as they will get deleted when we delete the old node. + //A better way to do this would be to steal the transforms from the old + //nodes, and make sure they're not deleted later, but this is impractical + //right now as we would also have to migrate all the animation curves. + + + //FRTScaleList scaleTransforms; + + SimdTransform accumulatedWorldTransform; + accumulatedWorldTransform.setIdentity(); + + uint32 numTransforms = targetNode->GetTransformCount(); + + for (uint32 i=0; iGetTransforms()[i])->ToMatrix(); + SimdVector3 pos(mat.GetTranslation().x,mat.GetTranslation().y,mat.GetTranslation().z); + + SimdMatrix3x3 rotMat( + mat.m[0][0],mat.m[0][1],mat.m[0][2], + mat.m[1][0],mat.m[1][1],mat.m[1][2], + mat.m[2][0],mat.m[2][1],mat.m[2][2]); + + rotMat = rotMat.transpose(); + SimdTransform trans(rotMat,pos); + + //TODO: check pre or post multiply + accumulatedWorldTransform = accumulatedWorldTransform * trans; + + } + + //Then affect all of its geometry instances. + //Collect all the entities inside the entity vector and inside the children nodes +/* + FREntityList childEntities = n->GetEntities(); + FRSceneNodeList childrenToParse = n->GetChildren(); + + while (!childrenToParse.empty()) + { + FRSceneNode* child = *childrenToParse.begin(); + const FREntityList& e = child->GetEntities(); + //add the entities of that child + childEntities.insert(childEntities.end(), e.begin(), e.end()); + //queue the grand-children nodes + childrenToParse.insert(childrenToParse.end(), child->GetChildren().begin(), child->GetChildren().end()); + childrenToParse.erase(childrenToParse.begin()); + + } +*/ + //now check which ones are geometry mesh (right now an entity is only derived by mesh + //but do this to avoid problems in the future) +/* + for (FREntityList::iterator itT = childEntities.begin(); itT != childEntities.end(); itT++) + { + + if ((*itT)->GetType() == FREntity::MESH || (*itT)->GetType() == FREntity::MESH_CONTROLLER) + + { + + FRMesh* cMesh = (FRMesh*)*itT; + + //while we're here, bake the scaling transforms into the meshes + + BakeScalingIntoMesh(cMesh, scaleTransforms); + + controller->AddBindMesh((FRMesh*)*itT); + + } + + } +*/ + + + ///////////////////////////////////////////////////////////////////// + //We're done with the targets. Now take care of the physics shapes. + FCDPhysicsRigidBody* rigidBody = rbInstance->FlattenRigidBody(); + FCDPhysicsMaterial* mat = rigidBody->GetPhysicsMaterial(); + FCDPhysicsShapeList shapes = rigidBody->GetPhysicsShapeList(); + + CollisionShape* collisionShape = 0; + + + FCDPhysicsParameter* dyn = (FCDPhysicsParameter*)rigidBody->FindParameterByReference(DAE_DYNAMIC_ELEMENT); + + bool isDynamic = true; + + if (dyn) + { + isDynamic = *dyn->GetValue(); + printf("isDynamic %i\n",isDynamic); + } + + for (uint32 i=0; iGetType();// + //controller->SetDensity(OldShape->GetDensity()); + + + if (OldShape->GetGeometryInstance()) + { + printf("mesh/convex geometry\n"); + + FCDGeometry* geoTemp = (FCDGeometry*)(OldShape->GetGeometryInstance()->GetEntity()); + + FCDGeometryMesh* colladaMesh = geoTemp->GetMesh(); + + + if (colladaMesh) + { + + if (1) + { + bool useConvexHull = false; + + //useConvexHull uses just the points. works, but there is no rendering at the moment + //for convex hull shapes + if (useConvexHull) + { + int count = colladaMesh->GetVertexSourceCount(); + for (int i=0;iGetVertexSource(i); + + if (geomSource->GetSourceType()==FUDaeGeometryInput::POSITION) + { + + int numPoints = geomSource->GetSourceData().size()/3; + SimdPoint3* points = new SimdPoint3[numPoints]; + for (int p=0;pGetSourceData()[p*3], + geomSource->GetSourceData()[p*3+1], + geomSource->GetSourceData()[p*3+2]); + } + + + + collisionShape = new ConvexHullShape(points,numPoints); + + delete points; + + break; + } + } + + } + else + { + TriangleMesh* trimesh = new TriangleMesh(); + + int polyCount = colladaMesh->GetPolygonsCount(); + for (uint32 j=0; jGetPolygons(j); + poly->Triangulate(); + + int numfaces = poly->GetFaceCount(); + int numfacevertex = poly->GetFaceVertexCount(); + + std::vector dataIndices; + + + //for (FCDGeometryPolygonsInputList::iterator itI = poly->idxOwners.begin(); itI != idxOwners.end(); ++itI) + //{ + // UInt32List* indices = &(*itI)->indices; + // dataIndices.push_back(*indices); + //} + + + + + FCDGeometryPolygonsInput* inputs = poly->FindInput(FUDaeGeometryInput::POSITION); + + + int startIndex = 0; + for (int p=0;pGetFaceVertexCounts()[p]; + + switch (numfacevertices) + { + case 3: + { + + //float value = inputs->source->GetSourceData()[index]; + + int offset = poly->GetFaceVertexOffset(p); + int index; + index = inputs->indices[offset]; + + SimdVector3 vertex0( + inputs->source->GetSourceData()[index*3], + inputs->source->GetSourceData()[index*3+1], + inputs->source->GetSourceData()[index*3+2]); + + index = inputs->indices[offset+1]; + + SimdVector3 vertex1( + inputs->source->GetSourceData()[index*3], + inputs->source->GetSourceData()[index*3+1], + inputs->source->GetSourceData()[index*3+2]); + + index = inputs->indices[offset+2]; + + SimdVector3 vertex2( + inputs->source->GetSourceData()[index*3], + inputs->source->GetSourceData()[index*3+1], + inputs->source->GetSourceData()[index*3+2]); + + + trimesh->AddTriangle(vertex0,vertex1,vertex2); + break; + } + + case 4: + { + int offset = poly->GetFaceVertexOffset(p); + int index; + index = inputs->indices[offset]; + + SimdVector3 vertex0( + inputs->source->GetSourceData()[index*3], + inputs->source->GetSourceData()[index*3+1], + inputs->source->GetSourceData()[index*3+2]); + + index = inputs->indices[offset+1]; + + SimdVector3 vertex1( + inputs->source->GetSourceData()[index*3], + inputs->source->GetSourceData()[index*3+1], + inputs->source->GetSourceData()[index*3+2]); + + index = inputs->indices[offset+2]; + + SimdVector3 vertex2( + inputs->source->GetSourceData()[index*3], + inputs->source->GetSourceData()[index*3+1], + inputs->source->GetSourceData()[index*3+2]); + + index = inputs->indices[offset+3]; + + SimdVector3 vertex3( + inputs->source->GetSourceData()[index*3], + inputs->source->GetSourceData()[index*3+1], + inputs->source->GetSourceData()[index*3+2]); + + trimesh->AddTriangle(vertex0,vertex1,vertex2); + trimesh->AddTriangle(vertex0,vertex2,vertex3); + + break; + } + + default: + { + } + } + } + + if (colladaMesh->m_convex || isDynamic) + { + collisionShape = new ConvexTriangleMeshShape(trimesh); + } else + { + collisionShape = new TriangleMeshShape(trimesh); + } + + + } + + + } + + + } else + { + + //should be static triangle mesh! + + //FRMesh* cMesh = ToFREntityGeometry(geoTemp); + //BakeScalingIntoMesh(cMesh, scaleTransforms); + + for (uint32 j=0; jGetPolygonsCount(); j++) + { + + /* + FRMeshPhysicsShape* NewShape = new FRMeshPhysicsShape(controller); + + if (!NewShape->CreateTriangleMesh(cMesh, j, true)) + + { + + SAFE_DELETE(NewShape); + + continue; + + } + if (mat) + { + NewShape->SetMaterial(mat->GetStaticFriction(), mat->GetDynamicFriction(), mat->GetRestitution()); + //FIXME + //NewShape->material->setFrictionCombineMode(); + //NewShape->material->setSpring(); + } + + controller->AddShape(NewShape); + + */ + } + } + } + + + + } + + else + + { + + //FRMeshPhysicsShape* NewShape = new FRMeshPhysicsShape(controller); + + FCDPhysicsAnalyticalGeometry* analGeom = OldShape->GetAnalyticalGeometry(); + + //increse the following value for nicer shapes with more vertices + + uint16 superEllipsoidSubdivisionLevel = 2; + + if (!analGeom) + + continue; + + switch (analGeom->GetGeomType()) + + { + + case FCDPhysicsAnalyticalGeometry::BOX: + + { + + FCDPASBox* box = (FCDPASBox*)analGeom; + printf("Box\n"); + collisionShape = new BoxShape(SimdVector3(box->halfExtents.x,box->halfExtents.y,box->halfExtents.z)); + + break; + + } + + case FCDPhysicsAnalyticalGeometry::PLANE: + + { + + FCDPASPlane* plane = (FCDPASPlane*)analGeom; + printf("Plane\n"); + break; + + } + + case FCDPhysicsAnalyticalGeometry::SPHERE: + + { + + FCDPASSphere* sphere = (FCDPASSphere*)analGeom; + collisionShape = new SphereShape(sphere->radius); + printf("Sphere\n"); + break; + + } + + case FCDPhysicsAnalyticalGeometry::CYLINDER: + + { + + //FIXME: only using the first radius of the cylinder + + FCDPASCylinder* cylinder = (FCDPASCylinder*)analGeom; + printf("Cylinder\n"); + + break; + + } + + case FCDPhysicsAnalyticalGeometry::CAPSULE: + + { + + //FIXME: only using the first radius of the capsule + + FCDPASCapsule* capsule = (FCDPASCapsule*)analGeom; + printf("Capsule\n"); + + break; + + } + + case FCDPhysicsAnalyticalGeometry::TAPERED_CAPSULE: + + { + + //FIXME: only using the first radius of the capsule + + FCDPASTaperedCapsule* tcapsule = (FCDPASTaperedCapsule*)analGeom; + printf("TaperedCapsule\n"); + break; + + } + + case FCDPhysicsAnalyticalGeometry::TAPERED_CYLINDER: + + { + + //FIXME: only using the first radius of the cylinder + + FCDPASTaperedCylinder* tcylinder = (FCDPASTaperedCylinder*)analGeom; + printf("TaperedCylinder\n"); + break; + + } + + default: + + { + + break; + + } + + } + + //controller->AddShape(NewShape); + } + + } + + + + FCDPhysicsParameter* mass = (FCDPhysicsParameter*)rigidBody->FindParameterByReference(DAE_MASS_ELEMENT); + + float mymass = 1.f; + + if (mass) + { + mymass = *mass->GetValue(); + printf("RB mass:%f\n",mymass); + } + + FCDPhysicsParameter* inertia = (FCDPhysicsParameter*)rigidBody->FindParameterByReference(DAE_INERTIA_ELEMENT); + + if (inertia) + { + inertia->GetValue();//this should be calculated from shape + } + + FCDPhysicsParameter* velocity = (FCDPhysicsParameter*)rigidBody->FindParameterByReference(DAE_VELOCITY_ELEMENT); + + if (velocity) + { + velocity->GetValue(); + } + + FCDPhysicsParameter* angularVelocity = (FCDPhysicsParameter*)rigidBody->FindParameterByReference(DAE_ANGULAR_VELOCITY_ELEMENT); + + if (angularVelocity) + { + angularVelocity->GetValue(); + } + + static int once = true; + + if (collisionShape) + { + once = false; + printf("create Physics Object\n"); + //void CreatePhysicsObject(bool isDynamic, float mass, const SimdTransform& startTransform,CollisionShape* shape) + + CreatePhysicsObject(isDynamic, mymass, accumulatedWorldTransform,collisionShape); + + + } + //controller->SetGlobalPose(n->CalculateWorldTransformation());//?? + + //SAFE_DELETE(rigidBody); + + } + + } + + } + + return true; +} + + + + + +//////////////////////////////////// + + + +GLDebugDrawer debugDrawer; + +int main(int argc,char** argv) +{ + + ///Setup a Physics Simulation Environment + CollisionDispatcher* dispatcher = new CollisionDispatcher(); + SimdVector3 worldAabbMin(-10000,-10000,-10000); + SimdVector3 worldAabbMax(10000,10000,10000); + BroadphaseInterface* broadphase = new AxisSweep3(worldAabbMin,worldAabbMax); + //BroadphaseInterface* broadphase = new SimpleBroadphase(); + physicsEnvironmentPtr = new CcdPhysicsEnvironment(dispatcher,broadphase); + physicsEnvironmentPtr->setDeactivationTime(2.f); + physicsEnvironmentPtr->setGravity(0,-10,0); + physicsEnvironmentPtr->setDebugDrawer(&debugDrawer); + + + /// Import Collada 1.4 Physics objects + + //char* filename = "analyticalGeomPhysicsTest.dae";//ColladaPhysics.dae"; + //char* filename = "colladaphysics_spherebox.dae"; + char* filename = "friction.dae"; + + + + FCDocument* document = new FCDocument(); + FUStatus status = document->LoadFromFile(filename); + bool success = status.IsSuccessful(); + printf ("Collada import %i\n",success); + + if (success) + { + const FCDPhysicsSceneNode* physicsSceneRoot = document->GetPhysicsSceneRoot(); + if (ConvertColladaPhysicsToBulletPhysics( physicsSceneRoot )) + { + printf("ConvertColladaPhysicsToBulletPhysics successfull\n"); + } else + { + printf("ConvertColladaPhysicsToBulletPhysics failed\n"); + } + } + + clientResetScene(); + + setCameraDistance(26.f); + + return glutmain(argc, argv,640,480,"Bullet Collada Physics Viewer. http://www.continuousphysics.com/Bullet/phpBB2/"); +} + +//to be implemented by the demo +void renderme() +{ + debugDrawer.SetDebugMode(getDebugMode()); + + + + float m[16]; + int i; + + + if (getDebugMode() & IDebugDraw::DBG_DisableBulletLCP) + { + //don't use Bullet, use quickstep + physicsEnvironmentPtr->setSolverType(0); + } else + { + //Bullet LCP solver + physicsEnvironmentPtr->setSolverType(1); + } + + if (getDebugMode() & IDebugDraw::DBG_EnableCCD) + { + physicsEnvironmentPtr->setCcdMode(3); + } else + { + physicsEnvironmentPtr->setCcdMode(0); + } + + + bool isSatEnabled = (getDebugMode() & IDebugDraw::DBG_EnableSatComparison); + + physicsEnvironmentPtr->EnableSatCollisionDetection(isSatEnabled); + + + + for (i=0;iGetRigidBody()->GetActivationState() == 1) //active + { + if (i & 1) + { + wireColor += SimdVector3 (1.f,0.f,0.f); + } else + { + wireColor += SimdVector3 (.5f,0.f,0.f); + } + } + if (physObjects[i]->GetRigidBody()->GetActivationState() == 2) //ISLAND_SLEEPING + { + if (i & 1) + { + wireColor += SimdVector3 (0.f,1.f, 0.f); + } else + { + wireColor += SimdVector3 (0.f,0.5f,0.f); + } + } + + char extraDebug[125]; + sprintf(extraDebug,"islId, Body=%i , %i",physObjects[i]->GetRigidBody()->m_islandTag1,physObjects[i]->GetRigidBody()->m_debugBodyId); + physObjects[i]->GetRigidBody()->GetCollisionShape()->SetExtraDebugInfo(extraDebug); + GL_ShapeDrawer::DrawOpenGL(m,physObjects[i]->GetRigidBody()->GetCollisionShape(),wireColor,getDebugMode()); + + ///this block is just experimental code to show some internal issues with replacing shapes on the fly. + if (getDebugMode()!=0 && (i>0)) + { + if (physObjects[i]->GetRigidBody()->GetCollisionShape()->GetShapeType() == EMPTY_SHAPE_PROXYTYPE) + { + physObjects[i]->GetRigidBody()->SetCollisionShape(gShapePtr[1]); + + //remove the persistent collision pairs that were created based on the previous shape + + BroadphaseProxy* bpproxy = physObjects[i]->GetRigidBody()->m_broadphaseHandle; + + physicsEnvironmentPtr->GetBroadphase()->CleanProxyFromPairs(bpproxy); + + SimdVector3 newinertia; + SimdScalar newmass = 10.f; + physObjects[i]->GetRigidBody()->GetCollisionShape()->CalculateLocalInertia(newmass,newinertia); + physObjects[i]->GetRigidBody()->setMassProps(newmass,newinertia); + physObjects[i]->GetRigidBody()->updateInertiaTensor(); + + } + + } + + + } + + if (!(getDebugMode() & IDebugDraw::DBG_NoHelpText)) + { + + float xOffset = 10.f; + float yStart = 20.f; + + float yIncr = -2.f; + + char buf[124]; + + glColor3f(0, 0, 0); + +#ifdef USE_QUICKPROF + + + if ( getDebugMode() & IDebugDraw::DBG_ProfileTimings) + { + static int counter = 0; + counter++; + std::map::iterator iter; + for (iter = Profiler::mProfileBlocks.begin(); iter != Profiler::mProfileBlocks.end(); ++iter) + { + char blockTime[128]; + sprintf(blockTime, "%s: %lf",&((*iter).first[0]),Profiler::getBlockTime((*iter).first, Profiler::BLOCK_CYCLE_SECONDS));//BLOCK_TOTAL_PERCENT)); + glRasterPos3f(xOffset,yStart,0); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),blockTime); + yStart += yIncr; + + } + } +#endif //USE_QUICKPROF + //profiling << Profiler::createStatsString(Profiler::BLOCK_TOTAL_PERCENT); + //<< std::endl; + + + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"mouse to interact"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"space to reset"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"cursor keys and z,x to navigate"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"i to toggle simulation, s single step"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"q to quit"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"d to toggle deactivation"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"a to draw temporal AABBs"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"h to toggle help text"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + bool useBulletLCP = !(getDebugMode() & IDebugDraw::DBG_DisableBulletLCP); + + bool useCCD = (getDebugMode() & IDebugDraw::DBG_EnableCCD); + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"m Bullet GJK = %i",!isSatEnabled); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"n Bullet LCP = %i",useBulletLCP); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"1 CCD mode (adhoc) = %i",useCCD); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"+- shooting speed = %10.2f",bulletSpeed); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + } + +} + +void clientMoveAndDisplay() +{ + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + + + physicsEnvironmentPtr->proceedDeltaTime(0.f,deltaTime); + + renderme(); + + glFlush(); + glutSwapBuffers(); + +} + + + +void clientDisplay(void) { + + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + + physicsEnvironmentPtr->UpdateAabbs(deltaTime); + + renderme(); + + + glFlush(); + glutSwapBuffers(); +} + + + +///make this positive to show stack falling from a distance +///this shows the penalty tresholds in action, springy/spungy look + +void clientResetScene() +{ + + //delete and reload, or keep transforms ready? +} + + + +void shootBox(const SimdVector3& destination) +{ + //no objects to shoot + if (!numObjects) + return; + + int i = numObjects-1; + + + + SimdVector3 linVel(destination[0]-eye[0],destination[1]-eye[1],destination[2]-eye[2]); + linVel.normalize(); + linVel*=bulletSpeed; + + physObjects[i]->setPosition(eye[0],eye[1],eye[2]); + physObjects[i]->setOrientation(0,0,0,1); + physObjects[i]->SetLinearVelocity(linVel[0],linVel[1],linVel[2],false); + physObjects[i]->SetAngularVelocity(0,0,0,false); +} + +void clientKeyboard(unsigned char key, int x, int y) +{ + + if (key == '.') + { + shootBox(SimdVector3(0,0,0)); + } + + if (key == '+') + { + bulletSpeed += 10.f; + } + if (key == '-') + { + bulletSpeed -= 10.f; + } + + defaultKeyboard(key, x, y); +} + +int gPickingConstraintId = 0; +SimdVector3 gOldPickingPos; +float gOldPickingDist = 0.f; +RigidBody* pickedBody = 0;//for deactivation state + + +SimdVector3 GetRayTo(int x,int y) +{ + float top = 1.f; + float bottom = -1.f; + float nearPlane = 1.f; + float tanFov = (top-bottom)*0.5f / nearPlane; + float fov = 2.0 * atanf (tanFov); + + SimdVector3 rayFrom(eye[0],eye[1],eye[2]); + SimdVector3 rayForward = -rayFrom; + rayForward.normalize(); + float farPlane = 600.f; + rayForward*= farPlane; + + SimdVector3 rightOffset; + SimdVector3 vertical(0.f,1.f,0.f); + SimdVector3 hor; + hor = rayForward.cross(vertical); + hor.normalize(); + vertical = hor.cross(rayForward); + vertical.normalize(); + + float tanfov = tanf(0.5f*fov); + hor *= 2.f * farPlane * tanfov; + vertical *= 2.f * farPlane * tanfov; + SimdVector3 rayToCenter = rayFrom + rayForward; + SimdVector3 dHor = hor * 1.f/float(glutScreenWidth); + SimdVector3 dVert = vertical * 1.f/float(glutScreenHeight); + SimdVector3 rayTo = rayToCenter - 0.5f * hor + 0.5f * vertical; + rayTo += x * dHor; + rayTo -= y * dVert; + return rayTo; +} +void clientMouseFunc(int button, int state, int x, int y) +{ + //printf("button %i, state %i, x=%i,y=%i\n",button,state,x,y); + //button 0, state 0 means left mouse down + + SimdVector3 rayTo = GetRayTo(x,y); + + switch (button) + { + case 2: + { + if (state==0) + { + shootBox(rayTo); + } + break; + }; + case 1: + { + if (state==0) + { + //apply an impulse + if (physicsEnvironmentPtr) + { + float hit[3]; + float normal[3]; + PHY_IPhysicsController* hitObj = physicsEnvironmentPtr->rayTest(0,eye[0],eye[1],eye[2],rayTo.getX(),rayTo.getY(),rayTo.getZ(),hit[0],hit[1],hit[2],normal[0],normal[1],normal[2]); + if (hitObj) + { + CcdPhysicsController* physCtrl = static_cast(hitObj); + RigidBody* body = physCtrl->GetRigidBody(); + if (body) + { + body->SetActivationState(ACTIVE_TAG); + SimdVector3 impulse = rayTo; + impulse.normalize(); + float impulseStrength = 10.f; + impulse *= impulseStrength; + SimdVector3 relPos( + hit[0] - body->getCenterOfMassPosition().getX(), + hit[1] - body->getCenterOfMassPosition().getY(), + hit[2] - body->getCenterOfMassPosition().getZ()); + + body->applyImpulse(impulse,relPos); + } + + } + + } + + } else + { + + } + break; + } + case 0: + { + if (state==0) + { + //add a point to point constraint for picking + if (physicsEnvironmentPtr) + { + float hit[3]; + float normal[3]; + PHY_IPhysicsController* hitObj = physicsEnvironmentPtr->rayTest(0,eye[0],eye[1],eye[2],rayTo.getX(),rayTo.getY(),rayTo.getZ(),hit[0],hit[1],hit[2],normal[0],normal[1],normal[2]); + if (hitObj) + { + + CcdPhysicsController* physCtrl = static_cast(hitObj); + RigidBody* body = physCtrl->GetRigidBody(); + + if (body) + { + pickedBody = body; + pickedBody->SetActivationState(DISABLE_DEACTIVATION); + + SimdVector3 pickPos(hit[0],hit[1],hit[2]); + + SimdVector3 localPivot = body->getCenterOfMassTransform().inverse() * pickPos; + + gPickingConstraintId = physicsEnvironmentPtr->createConstraint(physCtrl,0,PHY_POINT2POINT_CONSTRAINT, + localPivot.getX(), + localPivot.getY(), + localPivot.getZ(), + 0,0,0); + //printf("created constraint %i",gPickingConstraintId); + + //save mouse position for dragging + gOldPickingPos = rayTo; + + + SimdVector3 eyePos(eye[0],eye[1],eye[2]); + + gOldPickingDist = (pickPos-eyePos).length(); + + Point2PointConstraint* p2p = static_cast(physicsEnvironmentPtr->getConstraintById(gPickingConstraintId)); + if (p2p) + { + //very weak constraint for picking + p2p->m_setting.m_tau = 0.1f; + } + } + } + } + } else + { + if (gPickingConstraintId && physicsEnvironmentPtr) + { + physicsEnvironmentPtr->removeConstraint(gPickingConstraintId); + //printf("removed constraint %i",gPickingConstraintId); + gPickingConstraintId = 0; + pickedBody->ForceActivationState(ACTIVE_TAG); + pickedBody->m_deactivationTime = 0.f; + pickedBody = 0; + + + } + } + + break; + + } + default: + { + } + } + +} + +void clientMotionFunc(int x,int y) +{ + + if (gPickingConstraintId && physicsEnvironmentPtr) + { + + //move the constraint pivot + + Point2PointConstraint* p2p = static_cast(physicsEnvironmentPtr->getConstraintById(gPickingConstraintId)); + if (p2p) + { + //keep it at the same picking distance + + SimdVector3 newRayTo = GetRayTo(x,y); + SimdVector3 eyePos(eye[0],eye[1],eye[2]); + SimdVector3 dir = newRayTo-eyePos; + dir.normalize(); + dir *= gOldPickingDist; + + SimdVector3 newPos = eyePos + dir; + p2p->SetPivotB(newPos); + } + + } +} diff --git a/Demos/ConvexDecompositionDemo/ConvexDecompositionDemo.cpp b/Demos/ConvexDecompositionDemo/ConvexDecompositionDemo.cpp index be7d848fe..90dd723c4 100644 --- a/Demos/ConvexDecompositionDemo/ConvexDecompositionDemo.cpp +++ b/Demos/ConvexDecompositionDemo/ConvexDecompositionDemo.cpp @@ -1,152 +1,152 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + #include "cd_wavefront.h" -#include "ConvexBuilder.h" - - -#include "CcdPhysicsEnvironment.h" -#include "CcdPhysicsController.h" - -//#include "GL_LineSegmentShape.h" -#include "CollisionShapes/BoxShape.h" -#include "CollisionShapes/SphereShape.h" -#include "CollisionShapes/ConeShape.h" -#include "CollisionShapes/ConvexTriangleMeshShape.h" -#include "CollisionShapes/TriangleMesh.h" - - -#include "CollisionShapes/Simplex1to4Shape.h" -#include "CollisionShapes/EmptyShape.h" - -#include "Dynamics/RigidBody.h" -#include "CollisionDispatch/CollisionDispatcher.h" -#include "BroadphaseCollision/SimpleBroadphase.h" -#include "BroadphaseCollision/AxisSweep3.h" -#include "ConstraintSolver/Point2PointConstraint.h" -#include "ConstraintSolver/HingeConstraint.h" - -#include "quickprof.h" -#include "IDebugDraw.h" - -#include "GLDebugDrawer.h" - - -#include "PHY_Pro.h" -#include "BMF_Api.h" -#include //printf debugging - -float deltaTime = 1.f/60.f; -float bulletSpeed = 40.f; -bool createConstraint = false;//true; -#ifdef WIN32 -#if _MSC_VER >= 1310 -//only use SIMD Hull code under Win32 -#define USE_HULL 1 -#include "NarrowPhaseCollision/Hull.h" -#endif //_MSC_VER -#endif //WIN32 - - -#ifdef WIN32 //needed for glut.h -#include -#endif -#include -#include "GL_ShapeDrawer.h" - -#include "GlutStuff.h" - - -extern float eye[3]; -extern int glutScreenWidth; -extern int glutScreenHeight; - - -#ifdef _DEBUG -int numObjects = 4;//22; -#else -int numObjects = 120; -#endif - -const int maxNumObjects = 450; - -DefaultMotionState ms[maxNumObjects]; -CcdPhysicsController* physObjects[maxNumObjects] = {0,0,0,0}; -int shapeIndex[maxNumObjects]; - -SimdVector3 centroids[maxNumObjects]; - -CcdPhysicsEnvironment* physicsEnvironmentPtr = 0; - - -#define CUBE_HALF_EXTENTS 4 - -#define EXTRA_HEIGHT -20.f -//GL_LineSegmentShape shapeE(SimdPoint3(-50,0,0), -// SimdPoint3(50,0,0)); -static const int numShapes = 4; - -CollisionShape* shapePtr[maxNumObjects]; - - -CollisionShape* prebuildShapePtr[numShapes] = -{ - ///Please don't make the box sizes larger then 1000: the collision detection will be inaccurate. - ///See http://www.continuousphysics.com/Bullet/phpBB2/viewtopic.php?t=346 - - new BoxShape (SimdVector3(450,10,450)), - new BoxShape (SimdVector3(CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS)), - new SphereShape (CUBE_HALF_EXTENTS- 0.05f), - - //new ConeShape(CUBE_HALF_EXTENTS,2.f*CUBE_HALF_EXTENTS), - //new BU_Simplex1to4(SimdPoint3(-1,-1,-1),SimdPoint3(1,-1,-1),SimdPoint3(-1,1,-1),SimdPoint3(0,0,1)), - - //new EmptyShape(), - - new BoxShape (SimdVector3(0.4,1,0.8)) - -}; - - - - - -//////////////////////////////////// - -unsigned int tcount = 0; - - -GLDebugDrawer debugDrawer; - -int main(int argc,char** argv) -{ - - int i; - for (i=0;i0) - { - shapePtr[i] = prebuildShapePtr[1]; - shapeIndex[i] = 1;//sphere - } - else - { - shapeIndex[i] = 0; - shapePtr[i] = prebuildShapePtr[0]; - } - } +#include "ConvexBuilder.h" + + +#include "CcdPhysicsEnvironment.h" +#include "CcdPhysicsController.h" + +//#include "GL_LineSegmentShape.h" +#include "CollisionShapes/BoxShape.h" +#include "CollisionShapes/SphereShape.h" +#include "CollisionShapes/ConeShape.h" +#include "CollisionShapes/ConvexTriangleMeshShape.h" +#include "CollisionShapes/TriangleMesh.h" + + +#include "CollisionShapes/Simplex1to4Shape.h" +#include "CollisionShapes/EmptyShape.h" + +#include "Dynamics/RigidBody.h" +#include "CollisionDispatch/CollisionDispatcher.h" +#include "BroadphaseCollision/SimpleBroadphase.h" +#include "BroadphaseCollision/AxisSweep3.h" +#include "ConstraintSolver/Point2PointConstraint.h" +#include "ConstraintSolver/HingeConstraint.h" + +#include "quickprof.h" +#include "IDebugDraw.h" + +#include "GLDebugDrawer.h" + + +#include "PHY_Pro.h" +#include "BMF_Api.h" +#include //printf debugging + +float deltaTime = 1.f/60.f; +float bulletSpeed = 40.f; +bool createConstraint = false;//true; +#ifdef WIN32 +#if _MSC_VER >= 1310 +//only use SIMD Hull code under Win32 +#define USE_HULL 1 +#include "NarrowPhaseCollision/Hull.h" +#endif //_MSC_VER +#endif //WIN32 + + +#ifdef WIN32 //needed for glut.h +#include +#endif +#include +#include "GL_ShapeDrawer.h" + +#include "GlutStuff.h" + + +extern float eye[3]; +extern int glutScreenWidth; +extern int glutScreenHeight; + + +#ifdef _DEBUG +int numObjects = 4;//22; +#else +int numObjects = 120; +#endif + +const int maxNumObjects = 450; + +DefaultMotionState ms[maxNumObjects]; +CcdPhysicsController* physObjects[maxNumObjects] = {0,0,0,0}; +int shapeIndex[maxNumObjects]; + +SimdVector3 centroids[maxNumObjects]; + +CcdPhysicsEnvironment* physicsEnvironmentPtr = 0; + + +#define CUBE_HALF_EXTENTS 4 + +#define EXTRA_HEIGHT -20.f +//GL_LineSegmentShape shapeE(SimdPoint3(-50,0,0), +// SimdPoint3(50,0,0)); +static const int numShapes = 4; + +CollisionShape* shapePtr[maxNumObjects]; + + +CollisionShape* prebuildShapePtr[numShapes] = +{ + ///Please don't make the box sizes larger then 1000: the collision detection will be inaccurate. + ///See http://www.continuousphysics.com/Bullet/phpBB2/viewtopic.php?t=346 + + new BoxShape (SimdVector3(450,10,450)), + new BoxShape (SimdVector3(CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS)), + new SphereShape (CUBE_HALF_EXTENTS- 0.05f), + + //new ConeShape(CUBE_HALF_EXTENTS,2.f*CUBE_HALF_EXTENTS), + //new BU_Simplex1to4(SimdPoint3(-1,-1,-1),SimdPoint3(1,-1,-1),SimdPoint3(-1,1,-1),SimdPoint3(0,0,1)), + + //new EmptyShape(), + + new BoxShape (SimdVector3(0.4,1,0.8)) + +}; + + + + + +//////////////////////////////////// + +unsigned int tcount = 0; + + +GLDebugDrawer debugDrawer; + +int main(int argc,char** argv) +{ + + int i; + for (i=0;i0) + { + shapePtr[i] = prebuildShapePtr[1]; + shapeIndex[i] = 1;//sphere + } + else + { + shapeIndex[i] = 0; + shapePtr[i] = prebuildShapePtr[0]; + } + } ConvexDecomposition::WavefrontObj wo; char* filename = "file.obj"; @@ -167,9 +167,9 @@ int main(int argc,char** argv) virtual void ConvexDecompResult(ConvexDecomposition::ConvexResult &result) { - TriangleMesh* trimesh = new TriangleMesh(); - - SimdVector3 localScaling(6.f,6.f,6.f); + TriangleMesh* trimesh = new TriangleMesh(); + + SimdVector3 localScaling(6.f,6.f,6.f); //export data to .obj printf("ConvexResult\n"); @@ -196,12 +196,12 @@ int main(int argc,char** argv) unsigned int index0 = *src++; unsigned int index1 = *src++; unsigned int index2 = *src++; - SimdVector3 vertex0(result.mHullVertices[index0*3], result.mHullVertices[index0*3+1],result.mHullVertices[index0*3+2]); - SimdVector3 vertex1(result.mHullVertices[index1*3], result.mHullVertices[index1*3+1],result.mHullVertices[index1*3+2]); - SimdVector3 vertex2(result.mHullVertices[index2*3], result.mHullVertices[index2*3+1],result.mHullVertices[index2*3+2]); - vertex0 *= localScaling; - vertex1 *= localScaling; - vertex2 *= localScaling; + SimdVector3 vertex0(result.mHullVertices[index0*3], result.mHullVertices[index0*3+1],result.mHullVertices[index0*3+2]); + SimdVector3 vertex1(result.mHullVertices[index1*3], result.mHullVertices[index1*3+1],result.mHullVertices[index1*3+2]); + SimdVector3 vertex2(result.mHullVertices[index2*3], result.mHullVertices[index2*3+1],result.mHullVertices[index2*3+2]); + vertex0 *= localScaling; + vertex1 *= localScaling; + vertex2 *= localScaling; centroids[numObjects] += vertex0; centroids[numObjects]+= vertex1; centroids[numObjects]+= vertex2; @@ -221,17 +221,17 @@ int main(int argc,char** argv) unsigned int index2 = *src++; - SimdVector3 vertex0(result.mHullVertices[index0*3], result.mHullVertices[index0*3+1],result.mHullVertices[index0*3+2]); - SimdVector3 vertex1(result.mHullVertices[index1*3], result.mHullVertices[index1*3+1],result.mHullVertices[index1*3+2]); - SimdVector3 vertex2(result.mHullVertices[index2*3], result.mHullVertices[index2*3+1],result.mHullVertices[index2*3+2]); - vertex0 *= localScaling; - vertex1 *= localScaling; - vertex2 *= localScaling; - - vertex0 -= centroids[numObjects]; - vertex1 -= centroids[numObjects]; - vertex2 -= centroids[numObjects]; - + SimdVector3 vertex0(result.mHullVertices[index0*3], result.mHullVertices[index0*3+1],result.mHullVertices[index0*3+2]); + SimdVector3 vertex1(result.mHullVertices[index1*3], result.mHullVertices[index1*3+1],result.mHullVertices[index1*3+2]); + SimdVector3 vertex2(result.mHullVertices[index2*3], result.mHullVertices[index2*3+1],result.mHullVertices[index2*3+2]); + vertex0 *= localScaling; + vertex1 *= localScaling; + vertex2 *= localScaling; + + vertex0 -= centroids[numObjects]; + vertex1 -= centroids[numObjects]; + vertex2 -= centroids[numObjects]; + trimesh->AddTriangle(vertex0,vertex1,vertex2); index0+=mBaseCount; @@ -260,27 +260,27 @@ int main(int argc,char** argv) if (tcount) { numObjects = 1; //always have the ground object first - - TriangleMesh* trimesh = new TriangleMesh(); - - SimdVector3 localScaling(6.f,6.f,6.f); - - for (int i=0;iAddTriangle(vertex0,vertex1,vertex2); - } + + TriangleMesh* trimesh = new TriangleMesh(); + + SimdVector3 localScaling(6.f,6.f,6.f); + + for (int i=0;iAddTriangle(vertex0,vertex1,vertex2); + } shapePtr[numObjects++] = new ConvexTriangleMeshShape(trimesh); } @@ -330,798 +330,798 @@ int main(int argc,char** argv) } - - CollisionDispatcher* dispatcher = new CollisionDispatcher(); - - - SimdVector3 worldAabbMin(-10000,-10000,-10000); - SimdVector3 worldAabbMax(10000,10000,10000); - - BroadphaseInterface* broadphase = new AxisSweep3(worldAabbMin,worldAabbMax); - //BroadphaseInterface* broadphase = new SimpleBroadphase(); - - physicsEnvironmentPtr = new CcdPhysicsEnvironment(dispatcher,broadphase); - physicsEnvironmentPtr->setDeactivationTime(2.f); - - physicsEnvironmentPtr->setGravity(0,-10,0); - PHY_ShapeProps shapeProps; - - shapeProps.m_do_anisotropic = false; - shapeProps.m_do_fh = false; - shapeProps.m_do_rot_fh = false; - shapeProps.m_friction_scaling[0] = 1.; - shapeProps.m_friction_scaling[1] = 1.; - shapeProps.m_friction_scaling[2] = 1.; - - shapeProps.m_inertia = 1.f; - shapeProps.m_lin_drag = 0.2f; - shapeProps.m_ang_drag = 0.1f; - shapeProps.m_mass = 10.0f; - - PHY_MaterialProps materialProps; - materialProps.m_friction = 10.5f; - materialProps.m_restitution = 0.0f; - - CcdConstructionInfo ccdObjectCi; - ccdObjectCi.m_friction = 0.5f; - - ccdObjectCi.m_linearDamping = shapeProps.m_lin_drag; - ccdObjectCi.m_angularDamping = shapeProps.m_ang_drag; - - SimdTransform tr; - tr.setIdentity(); - - - - for (i=0;iSetMargin(0.05f); - - - - bool isDyna = i>0; - //if (i==1) - // isDyna=false; - - if (0)//i==1) - { - SimdQuaternion orn(0,0,0.1*SIMD_HALF_PI); - ms[i].setWorldOrientation(orn.x(),orn.y(),orn.z(),orn[3]); - } - - - if (i>0) - { - - switch (i) - { - case 1: - { - ms[i].setWorldPosition(0,10,0); - //for testing, rotate the ground cube so the stack has to recover a bit - - break; - } - case 2: - { - ms[i].setWorldPosition(0,8,2); - break; - } - default: - ms[i].setWorldPosition(0,i*CUBE_HALF_EXTENTS*2 - CUBE_HALF_EXTENTS,0); - } - - float quatIma0,quatIma1,quatIma2,quatReal; - SimdQuaternion quat; - SimdVector3 axis(0,0,1); - SimdScalar angle=0.5f; - - quat.setRotation(axis,angle); - - ms[i].setWorldOrientation(quat.getX(),quat.getY(),quat.getZ(),quat[3]); - - - - } else - { - ms[i].setWorldPosition(0,-10+EXTRA_HEIGHT,0); - - } - - ccdObjectCi.m_MotionState = &ms[i]; - ccdObjectCi.m_gravity = SimdVector3(0,0,0); - ccdObjectCi.m_localInertiaTensor =SimdVector3(0,0,0); - if (!isDyna) - { - shapeProps.m_mass = 0.f; - ccdObjectCi.m_mass = shapeProps.m_mass; - ccdObjectCi.m_collisionFlags = CollisionObject::isStatic; - } - else - { - shapeProps.m_mass = 1.f; - ccdObjectCi.m_mass = shapeProps.m_mass; - ccdObjectCi.m_collisionFlags = 0; - } - - - SimdVector3 localInertia; - if (shapePtr[shapeIndex[i]]->GetShapeType() == EMPTY_SHAPE_PROXYTYPE) - { - //take inertia from first shape - shapePtr[1]->CalculateLocalInertia(shapeProps.m_mass,localInertia); - } else - { - shapePtr[shapeIndex[i]]->CalculateLocalInertia(shapeProps.m_mass,localInertia); - } - ccdObjectCi.m_localInertiaTensor = localInertia; - - ccdObjectCi.m_collisionShape = shapePtr[shapeIndex[i]]; - - - physObjects[i]= new CcdPhysicsController( ccdObjectCi); - - // Only do CCD if motion in one timestep (1.f/60.f) exceeds CUBE_HALF_EXTENTS - physObjects[i]->GetRigidBody()->m_ccdSquareMotionTreshold = CUBE_HALF_EXTENTS; - - //Experimental: better estimation of CCD Time of Impact: - //physObjects[i]->GetRigidBody()->m_ccdSweptShereRadius = 0.5*CUBE_HALF_EXTENTS; - - physicsEnvironmentPtr->addCcdPhysicsController( physObjects[i]); - - if (i==1) - { - //physObjects[i]->SetAngularVelocity(0,0,-2,true); - } - - physicsEnvironmentPtr->setDebugDrawer(&debugDrawer); - - } - - - //create a constraint - if (createConstraint) - { - //physObjects[i]->SetAngularVelocity(0,0,-2,true); - int constraintId; - - float pivotX=CUBE_HALF_EXTENTS, - pivotY=-CUBE_HALF_EXTENTS, - pivotZ=CUBE_HALF_EXTENTS; - - float axisX=1,axisY=0,axisZ=0; - - - - HingeConstraint* hinge = 0; - - SimdVector3 pivotInA(CUBE_HALF_EXTENTS,-CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS); - SimdVector3 pivotInB(-CUBE_HALF_EXTENTS,-CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS); - SimdVector3 axisInA(0,1,0); - SimdVector3 axisInB(0,-1,0); - - RigidBody* rb0 = physObjects[1]->GetRigidBody(); - RigidBody* rb1 = physObjects[2]->GetRigidBody(); - - hinge = new HingeConstraint( - *rb0, - *rb1,pivotInA,pivotInB,axisInA,axisInB); - - physicsEnvironmentPtr->m_constraints.push_back(hinge); - - hinge->SetUserConstraintId(100); - hinge->SetUserConstraintType(PHY_LINEHINGE_CONSTRAINT); - - } - - - - - clientResetScene(); - - setCameraDistance(26.f); - - return glutmain(argc, argv,640,480,"Bullet Physics Demo. http://www.continuousphysics.com/Bullet/phpBB2/"); -} - -//to be implemented by the demo -void renderme() -{ - debugDrawer.SetDebugMode(getDebugMode()); - - //render the hinge axis - if (createConstraint) - { - SimdVector3 color(1,0,0); - SimdVector3 dirLocal(0,1,0); - SimdVector3 pivotInA(CUBE_HALF_EXTENTS,-CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS); - SimdVector3 pivotInB(-CUBE_HALF_EXTENTS,-CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS); - SimdVector3 from = physObjects[1]->GetRigidBody()->getCenterOfMassTransform()(pivotInA); - SimdVector3 fromB = physObjects[2]->GetRigidBody()->getCenterOfMassTransform()(pivotInB); - SimdVector3 dirWorldA = physObjects[1]->GetRigidBody()->getCenterOfMassTransform().getBasis() * dirLocal ; - SimdVector3 dirWorldB = physObjects[2]->GetRigidBody()->getCenterOfMassTransform().getBasis() * dirLocal ; - debugDrawer.DrawLine(from,from+dirWorldA,color); - debugDrawer.DrawLine(fromB,fromB+dirWorldB,color); - } - - float m[16]; - int i; - - - if (getDebugMode() & IDebugDraw::DBG_DisableBulletLCP) - { - //don't use Bullet, use quickstep - physicsEnvironmentPtr->setSolverType(0); - } else - { - //Bullet LCP solver - physicsEnvironmentPtr->setSolverType(1); - } - - if (getDebugMode() & IDebugDraw::DBG_EnableCCD) - { - physicsEnvironmentPtr->setCcdMode(3); - } else - { - physicsEnvironmentPtr->setCcdMode(0); - } - - - bool isSatEnabled = (getDebugMode() & IDebugDraw::DBG_EnableSatComparison); - - physicsEnvironmentPtr->EnableSatCollisionDetection(isSatEnabled); - - -#ifdef USE_HULL - //some testing code for SAT - if (isSatEnabled) - { - for (int s=0;sIsPolyhedral()) - { - PolyhedralConvexShape* polyhedron = static_cast(shape); - if (!polyhedron->m_optionalHull) - { - //first convert vertices in 'Point3' format - int numPoints = polyhedron->GetNumVertices(); - Point3* points = new Point3[numPoints+1]; - //first 4 points should not be co-planar, so add central point to satisfy MakeHull - points[0] = Point3(0.f,0.f,0.f); - - SimdVector3 vertex; - for (int p=0;pGetVertex(p,vertex); - points[p+1] = Point3(vertex.getX(),vertex.getY(),vertex.getZ()); - } - - Hull* hull = Hull::MakeHull(numPoints+1,points); - polyhedron->m_optionalHull = hull; - } - - } - } - - } -#endif //USE_HULL - - - for (i=0;iGetRigidBody()->GetActivationState() == 1) //active - { - if (i & 1) - { - wireColor += SimdVector3 (1.f,0.f,0.f); - } else - { - wireColor += SimdVector3 (.5f,0.f,0.f); - } - } - if (physObjects[i]->GetRigidBody()->GetActivationState() == 2) //ISLAND_SLEEPING - { - if (i & 1) - { - wireColor += SimdVector3 (0.f,1.f, 0.f); - } else - { - wireColor += SimdVector3 (0.f,0.5f,0.f); - } - } - - char extraDebug[125]; - sprintf(extraDebug,"islId, Body=%i , %i",physObjects[i]->GetRigidBody()->m_islandTag1,physObjects[i]->GetRigidBody()->m_debugBodyId); - physObjects[i]->GetRigidBody()->GetCollisionShape()->SetExtraDebugInfo(extraDebug); - GL_ShapeDrawer::DrawOpenGL(m,physObjects[i]->GetRigidBody()->GetCollisionShape(),wireColor,getDebugMode()); - - ///this block is just experimental code to show some internal issues with replacing shapes on the fly. - if (getDebugMode()!=0 && (i>0)) - { - if (physObjects[i]->GetRigidBody()->GetCollisionShape()->GetShapeType() == EMPTY_SHAPE_PROXYTYPE) - { - physObjects[i]->GetRigidBody()->SetCollisionShape(shapePtr[1]); - - //remove the persistent collision pairs that were created based on the previous shape - - BroadphaseProxy* bpproxy = physObjects[i]->GetRigidBody()->m_broadphaseHandle; - - physicsEnvironmentPtr->GetBroadphase()->CleanProxyFromPairs(bpproxy); - - SimdVector3 newinertia; - SimdScalar newmass = 10.f; - physObjects[i]->GetRigidBody()->GetCollisionShape()->CalculateLocalInertia(newmass,newinertia); - physObjects[i]->GetRigidBody()->setMassProps(newmass,newinertia); - physObjects[i]->GetRigidBody()->updateInertiaTensor(); - - } - - } - - - } - - if (!(getDebugMode() & IDebugDraw::DBG_NoHelpText)) - { - - float xOffset = 10.f; - float yStart = 20.f; - - float yIncr = -2.f; - - char buf[124]; - - glColor3f(0, 0, 0); - -#ifdef USE_QUICKPROF - - - if ( getDebugMode() & IDebugDraw::DBG_ProfileTimings) - { - static int counter = 0; - counter++; - std::map::iterator iter; - for (iter = Profiler::mProfileBlocks.begin(); iter != Profiler::mProfileBlocks.end(); ++iter) - { - char blockTime[128]; - sprintf(blockTime, "%s: %lf",&((*iter).first[0]),Profiler::getBlockTime((*iter).first, Profiler::BLOCK_CYCLE_SECONDS));//BLOCK_TOTAL_PERCENT)); - glRasterPos3f(xOffset,yStart,0); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),blockTime); - yStart += yIncr; - - } - } -#endif //USE_QUICKPROF - //profiling << Profiler::createStatsString(Profiler::BLOCK_TOTAL_PERCENT); - //<< std::endl; - - - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"mouse to interact"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"space to reset"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"cursor keys and z,x to navigate"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"i to toggle simulation, s single step"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"q to quit"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"d to toggle deactivation"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"a to draw temporal AABBs"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"h to toggle help text"); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - bool useBulletLCP = !(getDebugMode() & IDebugDraw::DBG_DisableBulletLCP); - - bool useCCD = (getDebugMode() & IDebugDraw::DBG_EnableCCD); - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"m Bullet GJK = %i",!isSatEnabled); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"n Bullet LCP = %i",useBulletLCP); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"1 CCD mode (adhoc) = %i",useCCD); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - glRasterPos3f(xOffset,yStart,0); - sprintf(buf,"+- shooting speed = %10.2f",bulletSpeed); - BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); - yStart += yIncr; - - } - -} - -void clientMoveAndDisplay() -{ - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - - - - physicsEnvironmentPtr->proceedDeltaTime(0.f,deltaTime); - - renderme(); - - glFlush(); - glutSwapBuffers(); - -} - - - -void clientDisplay(void) { - - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - - - physicsEnvironmentPtr->UpdateAabbs(deltaTime); - - renderme(); - - - glFlush(); - glutSwapBuffers(); -} - - - -///make this positive to show stack falling from a distance -///this shows the penalty tresholds in action, springy/spungy look - -void clientResetScene() -{ - - int i; - for (i=0;i0) - { - - if ((getDebugMode() & IDebugDraw::DBG_NoHelpText)) - { - if (physObjects[i]->GetRigidBody()->GetCollisionShape()->GetShapeType() == BOX_SHAPE_PROXYTYPE) - { - physObjects[i]->GetRigidBody()->SetCollisionShape(shapePtr[2]); - } else - { - physObjects[i]->GetRigidBody()->SetCollisionShape(shapePtr[1]); - } - - BroadphaseProxy* bpproxy = physObjects[i]->GetRigidBody()->m_broadphaseHandle; - physicsEnvironmentPtr->GetBroadphase()->CleanProxyFromPairs(bpproxy); - } - - int p = i; - if (tcount) - { - if (p>2) - p=2; - } - - //stack them - int colsize = 10; - if (tcount) - colsize = 2; - int row = (p*CUBE_HALF_EXTENTS*2)/(colsize*2*CUBE_HALF_EXTENTS); - int row2 = row; - int col = (p)%(colsize)-colsize/2; - - - if (col>3) - { - col=11; - row2 |=1; - } - - SimdVector3 position(col*2*CUBE_HALF_EXTENTS + (row2%2)*CUBE_HALF_EXTENTS, - row*2*CUBE_HALF_EXTENTS+CUBE_HALF_EXTENTS+EXTRA_HEIGHT,0); - - if (tcount) - { - if (p==2) - { - position += centroids[i]; - } - } - physObjects[i]->setPosition(position[0],position[1],position[2]); - physObjects[i]->setOrientation(0,0,0,1); - physObjects[i]->SetLinearVelocity(0,0,0,false); - physObjects[i]->SetAngularVelocity(0,0,0,false); - } - } -} - - - -void shootBox(const SimdVector3& destination) -{ - int i = numObjects-1; - - - - SimdVector3 linVel(destination[0]-eye[0],destination[1]-eye[1],destination[2]-eye[2]); - linVel.normalize(); - linVel*=bulletSpeed; - - physObjects[i]->setPosition(eye[0],eye[1],eye[2]); - physObjects[i]->setOrientation(0,0,0,1); - physObjects[i]->SetLinearVelocity(linVel[0],linVel[1],linVel[2],false); - physObjects[i]->SetAngularVelocity(0,0,0,false); -} - -void clientKeyboard(unsigned char key, int x, int y) -{ - - if (key == '.') - { - shootBox(SimdVector3(0,0,0)); - } - - if (key == '+') - { - bulletSpeed += 10.f; - } - if (key == '-') - { - bulletSpeed -= 10.f; - } - - defaultKeyboard(key, x, y); -} - -int gPickingConstraintId = 0; -SimdVector3 gOldPickingPos; -float gOldPickingDist = 0.f; -RigidBody* pickedBody = 0;//for deactivation state - - -SimdVector3 GetRayTo(int x,int y) -{ - float top = 1.f; - float bottom = -1.f; - float nearPlane = 1.f; - float tanFov = (top-bottom)*0.5f / nearPlane; - float fov = 2.0 * atanf (tanFov); - - SimdVector3 rayFrom(eye[0],eye[1],eye[2]); - SimdVector3 rayForward = -rayFrom; - rayForward.normalize(); - float farPlane = 600.f; - rayForward*= farPlane; - - SimdVector3 rightOffset; - SimdVector3 vertical(0.f,1.f,0.f); - SimdVector3 hor; - hor = rayForward.cross(vertical); - hor.normalize(); - vertical = hor.cross(rayForward); - vertical.normalize(); - - float tanfov = tanf(0.5f*fov); - hor *= 2.f * farPlane * tanfov; - vertical *= 2.f * farPlane * tanfov; - SimdVector3 rayToCenter = rayFrom + rayForward; - SimdVector3 dHor = hor * 1.f/float(glutScreenWidth); - SimdVector3 dVert = vertical * 1.f/float(glutScreenHeight); - SimdVector3 rayTo = rayToCenter - 0.5f * hor + 0.5f * vertical; - rayTo += x * dHor; - rayTo -= y * dVert; - return rayTo; -} -void clientMouseFunc(int button, int state, int x, int y) -{ - //printf("button %i, state %i, x=%i,y=%i\n",button,state,x,y); - //button 0, state 0 means left mouse down - - SimdVector3 rayTo = GetRayTo(x,y); - - switch (button) - { - case 2: - { - if (state==0) - { - shootBox(rayTo); - } - break; - }; - case 1: - { - if (state==0) - { - //apply an impulse - if (physicsEnvironmentPtr) - { - float hit[3]; - float normal[3]; - PHY_IPhysicsController* hitObj = physicsEnvironmentPtr->rayTest(0,eye[0],eye[1],eye[2],rayTo.getX(),rayTo.getY(),rayTo.getZ(),hit[0],hit[1],hit[2],normal[0],normal[1],normal[2]); - if (hitObj) - { - CcdPhysicsController* physCtrl = static_cast(hitObj); - RigidBody* body = physCtrl->GetRigidBody(); - if (body) - { - body->SetActivationState(ACTIVE_TAG); - SimdVector3 impulse = rayTo; - impulse.normalize(); - float impulseStrength = 10.f; - impulse *= impulseStrength; - SimdVector3 relPos( - hit[0] - body->getCenterOfMassPosition().getX(), - hit[1] - body->getCenterOfMassPosition().getY(), - hit[2] - body->getCenterOfMassPosition().getZ()); - - body->applyImpulse(impulse,relPos); - } - - } - - } - - } else - { - - } - break; - } - case 0: - { - if (state==0) - { - //add a point to point constraint for picking - if (physicsEnvironmentPtr) - { - float hit[3]; - float normal[3]; - PHY_IPhysicsController* hitObj = physicsEnvironmentPtr->rayTest(0,eye[0],eye[1],eye[2],rayTo.getX(),rayTo.getY(),rayTo.getZ(),hit[0],hit[1],hit[2],normal[0],normal[1],normal[2]); - if (hitObj) - { - - CcdPhysicsController* physCtrl = static_cast(hitObj); - RigidBody* body = physCtrl->GetRigidBody(); - - if (body) - { - pickedBody = body; - pickedBody->SetActivationState(DISABLE_DEACTIVATION); - - SimdVector3 pickPos(hit[0],hit[1],hit[2]); - - SimdVector3 localPivot = body->getCenterOfMassTransform().inverse() * pickPos; - - gPickingConstraintId = physicsEnvironmentPtr->createConstraint(physCtrl,0,PHY_POINT2POINT_CONSTRAINT, - localPivot.getX(), - localPivot.getY(), - localPivot.getZ(), - 0,0,0); - //printf("created constraint %i",gPickingConstraintId); - - //save mouse position for dragging - gOldPickingPos = rayTo; - - - SimdVector3 eyePos(eye[0],eye[1],eye[2]); - - gOldPickingDist = (pickPos-eyePos).length(); - - Point2PointConstraint* p2p = static_cast(physicsEnvironmentPtr->getConstraintById(gPickingConstraintId)); - if (p2p) - { - //very weak constraint for picking - p2p->m_setting.m_tau = 0.1f; - } - } - } - } - } else - { - if (gPickingConstraintId && physicsEnvironmentPtr) - { - physicsEnvironmentPtr->removeConstraint(gPickingConstraintId); - //printf("removed constraint %i",gPickingConstraintId); - gPickingConstraintId = 0; - pickedBody->ForceActivationState(ACTIVE_TAG); - pickedBody->m_deactivationTime = 0.f; - pickedBody = 0; - - - } - } - - break; - - } - default: - { - } - } - -} - -void clientMotionFunc(int x,int y) -{ - - if (gPickingConstraintId && physicsEnvironmentPtr) - { - - //move the constraint pivot - - Point2PointConstraint* p2p = static_cast(physicsEnvironmentPtr->getConstraintById(gPickingConstraintId)); - if (p2p) - { - //keep it at the same picking distance - - SimdVector3 newRayTo = GetRayTo(x,y); - SimdVector3 eyePos(eye[0],eye[1],eye[2]); - SimdVector3 dir = newRayTo-eyePos; - dir.normalize(); - dir *= gOldPickingDist; - - SimdVector3 newPos = eyePos + dir; - p2p->SetPivotB(newPos); - } - - } -} + + CollisionDispatcher* dispatcher = new CollisionDispatcher(); + + + SimdVector3 worldAabbMin(-10000,-10000,-10000); + SimdVector3 worldAabbMax(10000,10000,10000); + + BroadphaseInterface* broadphase = new AxisSweep3(worldAabbMin,worldAabbMax); + //BroadphaseInterface* broadphase = new SimpleBroadphase(); + + physicsEnvironmentPtr = new CcdPhysicsEnvironment(dispatcher,broadphase); + physicsEnvironmentPtr->setDeactivationTime(2.f); + + physicsEnvironmentPtr->setGravity(0,-10,0); + PHY_ShapeProps shapeProps; + + shapeProps.m_do_anisotropic = false; + shapeProps.m_do_fh = false; + shapeProps.m_do_rot_fh = false; + shapeProps.m_friction_scaling[0] = 1.; + shapeProps.m_friction_scaling[1] = 1.; + shapeProps.m_friction_scaling[2] = 1.; + + shapeProps.m_inertia = 1.f; + shapeProps.m_lin_drag = 0.2f; + shapeProps.m_ang_drag = 0.1f; + shapeProps.m_mass = 10.0f; + + PHY_MaterialProps materialProps; + materialProps.m_friction = 10.5f; + materialProps.m_restitution = 0.0f; + + CcdConstructionInfo ccdObjectCi; + ccdObjectCi.m_friction = 0.5f; + + ccdObjectCi.m_linearDamping = shapeProps.m_lin_drag; + ccdObjectCi.m_angularDamping = shapeProps.m_ang_drag; + + SimdTransform tr; + tr.setIdentity(); + + + + for (i=0;iSetMargin(0.05f); + + + + bool isDyna = i>0; + //if (i==1) + // isDyna=false; + + if (0)//i==1) + { + SimdQuaternion orn(0,0,0.1*SIMD_HALF_PI); + ms[i].setWorldOrientation(orn.x(),orn.y(),orn.z(),orn[3]); + } + + + if (i>0) + { + + switch (i) + { + case 1: + { + ms[i].setWorldPosition(0,10,0); + //for testing, rotate the ground cube so the stack has to recover a bit + + break; + } + case 2: + { + ms[i].setWorldPosition(0,8,2); + break; + } + default: + ms[i].setWorldPosition(0,i*CUBE_HALF_EXTENTS*2 - CUBE_HALF_EXTENTS,0); + } + + float quatIma0,quatIma1,quatIma2,quatReal; + SimdQuaternion quat; + SimdVector3 axis(0,0,1); + SimdScalar angle=0.5f; + + quat.setRotation(axis,angle); + + ms[i].setWorldOrientation(quat.getX(),quat.getY(),quat.getZ(),quat[3]); + + + + } else + { + ms[i].setWorldPosition(0,-10+EXTRA_HEIGHT,0); + + } + + ccdObjectCi.m_MotionState = &ms[i]; + ccdObjectCi.m_gravity = SimdVector3(0,0,0); + ccdObjectCi.m_localInertiaTensor =SimdVector3(0,0,0); + if (!isDyna) + { + shapeProps.m_mass = 0.f; + ccdObjectCi.m_mass = shapeProps.m_mass; + ccdObjectCi.m_collisionFlags = CollisionObject::isStatic; + } + else + { + shapeProps.m_mass = 1.f; + ccdObjectCi.m_mass = shapeProps.m_mass; + ccdObjectCi.m_collisionFlags = 0; + } + + + SimdVector3 localInertia; + if (shapePtr[shapeIndex[i]]->GetShapeType() == EMPTY_SHAPE_PROXYTYPE) + { + //take inertia from first shape + shapePtr[1]->CalculateLocalInertia(shapeProps.m_mass,localInertia); + } else + { + shapePtr[shapeIndex[i]]->CalculateLocalInertia(shapeProps.m_mass,localInertia); + } + ccdObjectCi.m_localInertiaTensor = localInertia; + + ccdObjectCi.m_collisionShape = shapePtr[shapeIndex[i]]; + + + physObjects[i]= new CcdPhysicsController( ccdObjectCi); + + // Only do CCD if motion in one timestep (1.f/60.f) exceeds CUBE_HALF_EXTENTS + physObjects[i]->GetRigidBody()->m_ccdSquareMotionTreshold = CUBE_HALF_EXTENTS; + + //Experimental: better estimation of CCD Time of Impact: + //physObjects[i]->GetRigidBody()->m_ccdSweptShereRadius = 0.5*CUBE_HALF_EXTENTS; + + physicsEnvironmentPtr->addCcdPhysicsController( physObjects[i]); + + if (i==1) + { + //physObjects[i]->SetAngularVelocity(0,0,-2,true); + } + + physicsEnvironmentPtr->setDebugDrawer(&debugDrawer); + + } + + + //create a constraint + if (createConstraint) + { + //physObjects[i]->SetAngularVelocity(0,0,-2,true); + int constraintId; + + float pivotX=CUBE_HALF_EXTENTS, + pivotY=-CUBE_HALF_EXTENTS, + pivotZ=CUBE_HALF_EXTENTS; + + float axisX=1,axisY=0,axisZ=0; + + + + HingeConstraint* hinge = 0; + + SimdVector3 pivotInA(CUBE_HALF_EXTENTS,-CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS); + SimdVector3 pivotInB(-CUBE_HALF_EXTENTS,-CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS); + SimdVector3 axisInA(0,1,0); + SimdVector3 axisInB(0,-1,0); + + RigidBody* rb0 = physObjects[1]->GetRigidBody(); + RigidBody* rb1 = physObjects[2]->GetRigidBody(); + + hinge = new HingeConstraint( + *rb0, + *rb1,pivotInA,pivotInB,axisInA,axisInB); + + physicsEnvironmentPtr->m_constraints.push_back(hinge); + + hinge->SetUserConstraintId(100); + hinge->SetUserConstraintType(PHY_LINEHINGE_CONSTRAINT); + + } + + + + + clientResetScene(); + + setCameraDistance(26.f); + + return glutmain(argc, argv,640,480,"Bullet Physics Demo. http://www.continuousphysics.com/Bullet/phpBB2/"); +} + +//to be implemented by the demo +void renderme() +{ + debugDrawer.SetDebugMode(getDebugMode()); + + //render the hinge axis + if (createConstraint) + { + SimdVector3 color(1,0,0); + SimdVector3 dirLocal(0,1,0); + SimdVector3 pivotInA(CUBE_HALF_EXTENTS,-CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS); + SimdVector3 pivotInB(-CUBE_HALF_EXTENTS,-CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS); + SimdVector3 from = physObjects[1]->GetRigidBody()->getCenterOfMassTransform()(pivotInA); + SimdVector3 fromB = physObjects[2]->GetRigidBody()->getCenterOfMassTransform()(pivotInB); + SimdVector3 dirWorldA = physObjects[1]->GetRigidBody()->getCenterOfMassTransform().getBasis() * dirLocal ; + SimdVector3 dirWorldB = physObjects[2]->GetRigidBody()->getCenterOfMassTransform().getBasis() * dirLocal ; + debugDrawer.DrawLine(from,from+dirWorldA,color); + debugDrawer.DrawLine(fromB,fromB+dirWorldB,color); + } + + float m[16]; + int i; + + + if (getDebugMode() & IDebugDraw::DBG_DisableBulletLCP) + { + //don't use Bullet, use quickstep + physicsEnvironmentPtr->setSolverType(0); + } else + { + //Bullet LCP solver + physicsEnvironmentPtr->setSolverType(1); + } + + if (getDebugMode() & IDebugDraw::DBG_EnableCCD) + { + physicsEnvironmentPtr->setCcdMode(3); + } else + { + physicsEnvironmentPtr->setCcdMode(0); + } + + + bool isSatEnabled = (getDebugMode() & IDebugDraw::DBG_EnableSatComparison); + + physicsEnvironmentPtr->EnableSatCollisionDetection(isSatEnabled); + + +#ifdef USE_HULL + //some testing code for SAT + if (isSatEnabled) + { + for (int s=0;sIsPolyhedral()) + { + PolyhedralConvexShape* polyhedron = static_cast(shape); + if (!polyhedron->m_optionalHull) + { + //first convert vertices in 'Point3' format + int numPoints = polyhedron->GetNumVertices(); + Point3* points = new Point3[numPoints+1]; + //first 4 points should not be co-planar, so add central point to satisfy MakeHull + points[0] = Point3(0.f,0.f,0.f); + + SimdVector3 vertex; + for (int p=0;pGetVertex(p,vertex); + points[p+1] = Point3(vertex.getX(),vertex.getY(),vertex.getZ()); + } + + Hull* hull = Hull::MakeHull(numPoints+1,points); + polyhedron->m_optionalHull = hull; + } + + } + } + + } +#endif //USE_HULL + + + for (i=0;iGetRigidBody()->GetActivationState() == 1) //active + { + if (i & 1) + { + wireColor += SimdVector3 (1.f,0.f,0.f); + } else + { + wireColor += SimdVector3 (.5f,0.f,0.f); + } + } + if (physObjects[i]->GetRigidBody()->GetActivationState() == 2) //ISLAND_SLEEPING + { + if (i & 1) + { + wireColor += SimdVector3 (0.f,1.f, 0.f); + } else + { + wireColor += SimdVector3 (0.f,0.5f,0.f); + } + } + + char extraDebug[125]; + sprintf(extraDebug,"islId, Body=%i , %i",physObjects[i]->GetRigidBody()->m_islandTag1,physObjects[i]->GetRigidBody()->m_debugBodyId); + physObjects[i]->GetRigidBody()->GetCollisionShape()->SetExtraDebugInfo(extraDebug); + GL_ShapeDrawer::DrawOpenGL(m,physObjects[i]->GetRigidBody()->GetCollisionShape(),wireColor,getDebugMode()); + + ///this block is just experimental code to show some internal issues with replacing shapes on the fly. + if (getDebugMode()!=0 && (i>0)) + { + if (physObjects[i]->GetRigidBody()->GetCollisionShape()->GetShapeType() == EMPTY_SHAPE_PROXYTYPE) + { + physObjects[i]->GetRigidBody()->SetCollisionShape(shapePtr[1]); + + //remove the persistent collision pairs that were created based on the previous shape + + BroadphaseProxy* bpproxy = physObjects[i]->GetRigidBody()->m_broadphaseHandle; + + physicsEnvironmentPtr->GetBroadphase()->CleanProxyFromPairs(bpproxy); + + SimdVector3 newinertia; + SimdScalar newmass = 10.f; + physObjects[i]->GetRigidBody()->GetCollisionShape()->CalculateLocalInertia(newmass,newinertia); + physObjects[i]->GetRigidBody()->setMassProps(newmass,newinertia); + physObjects[i]->GetRigidBody()->updateInertiaTensor(); + + } + + } + + + } + + if (!(getDebugMode() & IDebugDraw::DBG_NoHelpText)) + { + + float xOffset = 10.f; + float yStart = 20.f; + + float yIncr = -2.f; + + char buf[124]; + + glColor3f(0, 0, 0); + +#ifdef USE_QUICKPROF + + + if ( getDebugMode() & IDebugDraw::DBG_ProfileTimings) + { + static int counter = 0; + counter++; + std::map::iterator iter; + for (iter = Profiler::mProfileBlocks.begin(); iter != Profiler::mProfileBlocks.end(); ++iter) + { + char blockTime[128]; + sprintf(blockTime, "%s: %lf",&((*iter).first[0]),Profiler::getBlockTime((*iter).first, Profiler::BLOCK_CYCLE_SECONDS));//BLOCK_TOTAL_PERCENT)); + glRasterPos3f(xOffset,yStart,0); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),blockTime); + yStart += yIncr; + + } + } +#endif //USE_QUICKPROF + //profiling << Profiler::createStatsString(Profiler::BLOCK_TOTAL_PERCENT); + //<< std::endl; + + + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"mouse to interact"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"space to reset"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"cursor keys and z,x to navigate"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"i to toggle simulation, s single step"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"q to quit"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"d to toggle deactivation"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"a to draw temporal AABBs"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"h to toggle help text"); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + bool useBulletLCP = !(getDebugMode() & IDebugDraw::DBG_DisableBulletLCP); + + bool useCCD = (getDebugMode() & IDebugDraw::DBG_EnableCCD); + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"m Bullet GJK = %i",!isSatEnabled); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"n Bullet LCP = %i",useBulletLCP); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"1 CCD mode (adhoc) = %i",useCCD); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + glRasterPos3f(xOffset,yStart,0); + sprintf(buf,"+- shooting speed = %10.2f",bulletSpeed); + BMF_DrawString(BMF_GetFont(BMF_kHelvetica10),buf); + yStart += yIncr; + + } + +} + +void clientMoveAndDisplay() +{ + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + + + physicsEnvironmentPtr->proceedDeltaTime(0.f,deltaTime); + + renderme(); + + glFlush(); + glutSwapBuffers(); + +} + + + +void clientDisplay(void) { + + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + + physicsEnvironmentPtr->UpdateAabbs(deltaTime); + + renderme(); + + + glFlush(); + glutSwapBuffers(); +} + + + +///make this positive to show stack falling from a distance +///this shows the penalty tresholds in action, springy/spungy look + +void clientResetScene() +{ + + int i; + for (i=0;i0) + { + + if ((getDebugMode() & IDebugDraw::DBG_NoHelpText)) + { + if (physObjects[i]->GetRigidBody()->GetCollisionShape()->GetShapeType() == BOX_SHAPE_PROXYTYPE) + { + physObjects[i]->GetRigidBody()->SetCollisionShape(shapePtr[2]); + } else + { + physObjects[i]->GetRigidBody()->SetCollisionShape(shapePtr[1]); + } + + BroadphaseProxy* bpproxy = physObjects[i]->GetRigidBody()->m_broadphaseHandle; + physicsEnvironmentPtr->GetBroadphase()->CleanProxyFromPairs(bpproxy); + } + + int p = i; + if (tcount) + { + if (p>2) + p=2; + } + + //stack them + int colsize = 10; + if (tcount) + colsize = 2; + int row = (p*CUBE_HALF_EXTENTS*2)/(colsize*2*CUBE_HALF_EXTENTS); + int row2 = row; + int col = (p)%(colsize)-colsize/2; + + + if (col>3) + { + col=11; + row2 |=1; + } + + SimdVector3 position(col*2*CUBE_HALF_EXTENTS + (row2%2)*CUBE_HALF_EXTENTS, + row*2*CUBE_HALF_EXTENTS+CUBE_HALF_EXTENTS+EXTRA_HEIGHT,0); + + if (tcount) + { + if (p==2) + { + position += centroids[i]; + } + } + physObjects[i]->setPosition(position[0],position[1],position[2]); + physObjects[i]->setOrientation(0,0,0,1); + physObjects[i]->SetLinearVelocity(0,0,0,false); + physObjects[i]->SetAngularVelocity(0,0,0,false); + } + } +} + + + +void shootBox(const SimdVector3& destination) +{ + int i = numObjects-1; + + + + SimdVector3 linVel(destination[0]-eye[0],destination[1]-eye[1],destination[2]-eye[2]); + linVel.normalize(); + linVel*=bulletSpeed; + + physObjects[i]->setPosition(eye[0],eye[1],eye[2]); + physObjects[i]->setOrientation(0,0,0,1); + physObjects[i]->SetLinearVelocity(linVel[0],linVel[1],linVel[2],false); + physObjects[i]->SetAngularVelocity(0,0,0,false); +} + +void clientKeyboard(unsigned char key, int x, int y) +{ + + if (key == '.') + { + shootBox(SimdVector3(0,0,0)); + } + + if (key == '+') + { + bulletSpeed += 10.f; + } + if (key == '-') + { + bulletSpeed -= 10.f; + } + + defaultKeyboard(key, x, y); +} + +int gPickingConstraintId = 0; +SimdVector3 gOldPickingPos; +float gOldPickingDist = 0.f; +RigidBody* pickedBody = 0;//for deactivation state + + +SimdVector3 GetRayTo(int x,int y) +{ + float top = 1.f; + float bottom = -1.f; + float nearPlane = 1.f; + float tanFov = (top-bottom)*0.5f / nearPlane; + float fov = 2.0 * atanf (tanFov); + + SimdVector3 rayFrom(eye[0],eye[1],eye[2]); + SimdVector3 rayForward = -rayFrom; + rayForward.normalize(); + float farPlane = 600.f; + rayForward*= farPlane; + + SimdVector3 rightOffset; + SimdVector3 vertical(0.f,1.f,0.f); + SimdVector3 hor; + hor = rayForward.cross(vertical); + hor.normalize(); + vertical = hor.cross(rayForward); + vertical.normalize(); + + float tanfov = tanf(0.5f*fov); + hor *= 2.f * farPlane * tanfov; + vertical *= 2.f * farPlane * tanfov; + SimdVector3 rayToCenter = rayFrom + rayForward; + SimdVector3 dHor = hor * 1.f/float(glutScreenWidth); + SimdVector3 dVert = vertical * 1.f/float(glutScreenHeight); + SimdVector3 rayTo = rayToCenter - 0.5f * hor + 0.5f * vertical; + rayTo += x * dHor; + rayTo -= y * dVert; + return rayTo; +} +void clientMouseFunc(int button, int state, int x, int y) +{ + //printf("button %i, state %i, x=%i,y=%i\n",button,state,x,y); + //button 0, state 0 means left mouse down + + SimdVector3 rayTo = GetRayTo(x,y); + + switch (button) + { + case 2: + { + if (state==0) + { + shootBox(rayTo); + } + break; + }; + case 1: + { + if (state==0) + { + //apply an impulse + if (physicsEnvironmentPtr) + { + float hit[3]; + float normal[3]; + PHY_IPhysicsController* hitObj = physicsEnvironmentPtr->rayTest(0,eye[0],eye[1],eye[2],rayTo.getX(),rayTo.getY(),rayTo.getZ(),hit[0],hit[1],hit[2],normal[0],normal[1],normal[2]); + if (hitObj) + { + CcdPhysicsController* physCtrl = static_cast(hitObj); + RigidBody* body = physCtrl->GetRigidBody(); + if (body) + { + body->SetActivationState(ACTIVE_TAG); + SimdVector3 impulse = rayTo; + impulse.normalize(); + float impulseStrength = 10.f; + impulse *= impulseStrength; + SimdVector3 relPos( + hit[0] - body->getCenterOfMassPosition().getX(), + hit[1] - body->getCenterOfMassPosition().getY(), + hit[2] - body->getCenterOfMassPosition().getZ()); + + body->applyImpulse(impulse,relPos); + } + + } + + } + + } else + { + + } + break; + } + case 0: + { + if (state==0) + { + //add a point to point constraint for picking + if (physicsEnvironmentPtr) + { + float hit[3]; + float normal[3]; + PHY_IPhysicsController* hitObj = physicsEnvironmentPtr->rayTest(0,eye[0],eye[1],eye[2],rayTo.getX(),rayTo.getY(),rayTo.getZ(),hit[0],hit[1],hit[2],normal[0],normal[1],normal[2]); + if (hitObj) + { + + CcdPhysicsController* physCtrl = static_cast(hitObj); + RigidBody* body = physCtrl->GetRigidBody(); + + if (body) + { + pickedBody = body; + pickedBody->SetActivationState(DISABLE_DEACTIVATION); + + SimdVector3 pickPos(hit[0],hit[1],hit[2]); + + SimdVector3 localPivot = body->getCenterOfMassTransform().inverse() * pickPos; + + gPickingConstraintId = physicsEnvironmentPtr->createConstraint(physCtrl,0,PHY_POINT2POINT_CONSTRAINT, + localPivot.getX(), + localPivot.getY(), + localPivot.getZ(), + 0,0,0); + //printf("created constraint %i",gPickingConstraintId); + + //save mouse position for dragging + gOldPickingPos = rayTo; + + + SimdVector3 eyePos(eye[0],eye[1],eye[2]); + + gOldPickingDist = (pickPos-eyePos).length(); + + Point2PointConstraint* p2p = static_cast(physicsEnvironmentPtr->getConstraintById(gPickingConstraintId)); + if (p2p) + { + //very weak constraint for picking + p2p->m_setting.m_tau = 0.1f; + } + } + } + } + } else + { + if (gPickingConstraintId && physicsEnvironmentPtr) + { + physicsEnvironmentPtr->removeConstraint(gPickingConstraintId); + //printf("removed constraint %i",gPickingConstraintId); + gPickingConstraintId = 0; + pickedBody->ForceActivationState(ACTIVE_TAG); + pickedBody->m_deactivationTime = 0.f; + pickedBody = 0; + + + } + } + + break; + + } + default: + { + } + } + +} + +void clientMotionFunc(int x,int y) +{ + + if (gPickingConstraintId && physicsEnvironmentPtr) + { + + //move the constraint pivot + + Point2PointConstraint* p2p = static_cast(physicsEnvironmentPtr->getConstraintById(gPickingConstraintId)); + if (p2p) + { + //keep it at the same picking distance + + SimdVector3 newRayTo = GetRayTo(x,y); + SimdVector3 eyePos(eye[0],eye[1],eye[2]); + SimdVector3 dir = newRayTo-eyePos; + dir.normalize(); + dir *= gOldPickingDist; + + SimdVector3 newPos = eyePos + dir; + p2p->SetPivotB(newPos); + } + + } +} diff --git a/Demos/OpenGL/GlutStuff.cpp b/Demos/OpenGL/GlutStuff.cpp index 1390efa71..db7761c98 100644 --- a/Demos/OpenGL/GlutStuff.cpp +++ b/Demos/OpenGL/GlutStuff.cpp @@ -90,7 +90,7 @@ bool stepping= true; bool singleStep = false; -static bool idle = false; +static bool idle = true; void toggleIdle() { @@ -347,7 +347,7 @@ int glutmain(int argc, char **argv,int width,int height,const char* title) { glutSpecialFunc(mySpecial); glutReshapeFunc(myReshape); //createMenu(); - glutIdleFunc(clientMoveAndDisplay); + glutIdleFunc(0);//clientMoveAndDisplay); glutMouseFunc(clientMouseFunc); glutMotionFunc(clientMotionFunc); glutDisplayFunc( clientDisplay ); diff --git a/Extras/FCollada/FCDocument/FCDGeometry.cpp b/Extras/FCollada/FCDocument/FCDGeometry.cpp index 2181015e6..8aec42d94 100644 --- a/Extras/FCollada/FCDocument/FCDGeometry.cpp +++ b/Extras/FCollada/FCDocument/FCDGeometry.cpp @@ -91,6 +91,36 @@ FUStatus FCDGeometry::LoadFromXML(xmlNode* geometryNode) status.AppendStatus(s->LoadFromXML(child)); break; } + else if (IsEquivalent(child->name, DAE_CONVEX_MESH_ELEMENT)) + { + //several cases can exist here... + //wait for fixed version of FCollada? + //assume and do instantiate? + + // Create a new mesh + FCDGeometryMesh* m = CreateMesh(); + m->m_convex = true; + FUUri url = ReadNodeUrl(child,"convex_hull_of"); + + if (!url.prefix.empty()) + { + FCDGeometry* entity = GetDocument()->FindGeometry(url.prefix); + if (entity) + { + printf("found convex_mesh%s\n",url.prefix); + //quick hack + this->mesh = entity->GetMesh(); + mesh->m_convex = true; + + } + + } + + + //status.AppendStatus(m->LoadFromXML(child)); + + break; + } else { return status.Fail(FS("Unknown child in with id: ") + TO_FSTRING(GetDaeId()), child->line); diff --git a/Extras/FCollada/FCDocument/FCDGeometryInstance.cpp b/Extras/FCollada/FCDocument/FCDGeometryInstance.cpp index cf39c5446..2e8d71d0e 100644 --- a/Extras/FCollada/FCDocument/FCDGeometryInstance.cpp +++ b/Extras/FCollada/FCDocument/FCDGeometryInstance.cpp @@ -15,7 +15,7 @@ #include "FCDocument/FCDEntity.h" #include "FCDocument/FCDGeometry.h" #include "FCDocument/FCDGeometryInstance.h" -#include "FCDocument/FCDGeometryMesh.h" +#include "FCDocument/FCDGeometryMesh.h" #include "FCDocument/FCDGeometryPolygons.h" #include "FCDocument/FCDMaterialInstance.h" #include "FUtils/FUDaeParser.h" @@ -23,38 +23,38 @@ using namespace FUDaeParser; using namespace FUDaeWriter; -// Parasitic: Write out the instantiation information to the xml node tree -xmlNode* FCDEntityInstance::WriteToXML(xmlNode* parentNode) const -{ - xmlNode* instanceNode = NULL; - if (entity != NULL) - { - const char* instanceEntityName; - switch (entity->GetType()) - { - case FCDEntity::ANIMATION: instanceEntityName = DAE_INSTANCE_ANIMATION_ELEMENT; break; - case FCDEntity::CAMERA: instanceEntityName = DAE_INSTANCE_CAMERA_ELEMENT; break; - case FCDEntity::CONTROLLER: instanceEntityName = DAE_INSTANCE_CONTROLLER_ELEMENT; break; - case FCDEntity::EFFECT: instanceEntityName = DAE_INSTANCE_EFFECT_ELEMENT; break; - case FCDEntity::GEOMETRY: instanceEntityName = DAE_INSTANCE_GEOMETRY_ELEMENT; break; - case FCDEntity::LIGHT: instanceEntityName = DAE_INSTANCE_LIGHT_ELEMENT; break; - case FCDEntity::MATERIAL: instanceEntityName = DAE_INSTANCE_MATERIAL_ELEMENT; break; - case FCDEntity::PHYSICS_MODEL: instanceEntityName = DAE_INSTANCE_PHYSICS_MODEL_ELEMENT; break; - case FCDEntity::PHYSICS_RIGID_BODY: instanceEntityName = DAE_INSTANCE_RIGID_BODY_ELEMENT; break; - case FCDEntity::PHYSICS_RIGID_CONSTRAINT: instanceEntityName = DAE_INSTANCE_RIGID_CONSTRAINT_ELEMENT; break; - case FCDEntity::SCENE_NODE: instanceEntityName = DAE_INSTANCE_NODE_ELEMENT; break; - - case FCDEntity::ANIMATION_CLIP: - case FCDEntity::ENTITY: - case FCDEntity::IMAGE: - case FCDEntity::TEXTURE: - default: instanceEntityName = DAEERR_UNKNOWN_ELEMENT; - } - - instanceNode = AddChild(parentNode, instanceEntityName); - AddAttribute(instanceNode, DAE_URL_ATTRIBUTE, string("#") + entity->GetDaeId()); - } - return instanceNode; +// Parasitic: Write out the instantiation information to the xml node tree +xmlNode* FCDEntityInstance::WriteToXML(xmlNode* parentNode) const +{ + xmlNode* instanceNode = NULL; + if (entity != NULL) + { + const char* instanceEntityName; + switch (entity->GetType()) + { + case FCDEntity::ANIMATION: instanceEntityName = DAE_INSTANCE_ANIMATION_ELEMENT; break; + case FCDEntity::CAMERA: instanceEntityName = DAE_INSTANCE_CAMERA_ELEMENT; break; + case FCDEntity::CONTROLLER: instanceEntityName = DAE_INSTANCE_CONTROLLER_ELEMENT; break; + case FCDEntity::EFFECT: instanceEntityName = DAE_INSTANCE_EFFECT_ELEMENT; break; + case FCDEntity::GEOMETRY: instanceEntityName = DAE_INSTANCE_GEOMETRY_ELEMENT; break; + case FCDEntity::LIGHT: instanceEntityName = DAE_INSTANCE_LIGHT_ELEMENT; break; + case FCDEntity::MATERIAL: instanceEntityName = DAE_INSTANCE_MATERIAL_ELEMENT; break; + case FCDEntity::PHYSICS_MODEL: instanceEntityName = DAE_INSTANCE_PHYSICS_MODEL_ELEMENT; break; + case FCDEntity::PHYSICS_RIGID_BODY: instanceEntityName = DAE_INSTANCE_RIGID_BODY_ELEMENT; break; + case FCDEntity::PHYSICS_RIGID_CONSTRAINT: instanceEntityName = DAE_INSTANCE_RIGID_CONSTRAINT_ELEMENT; break; + case FCDEntity::SCENE_NODE: instanceEntityName = DAE_INSTANCE_NODE_ELEMENT; break; + + case FCDEntity::ANIMATION_CLIP: + case FCDEntity::ENTITY: + case FCDEntity::IMAGE: + case FCDEntity::TEXTURE: + default: instanceEntityName = DAEERR_UNKNOWN_ELEMENT; + } + + instanceNode = AddChild(parentNode, instanceEntityName); + AddAttribute(instanceNode, DAE_URL_ATTRIBUTE, string("#") + entity->GetDaeId()); + } + return instanceNode; } FCDGeometryInstance::FCDGeometryInstance(FCDocument* document, FCDEntity* entity) : FCDEntityInstance(document, entity) @@ -150,19 +150,19 @@ FUStatus FCDGeometryInstance::LoadFromXML(xmlNode* instanceNode) return status; } - -// Write out the instantiation information to the xml node tree -xmlNode* FCDGeometryInstance::WriteToXML(xmlNode* parentNode) const -{ - xmlNode* instanceNode = FCDEntityInstance::WriteToXML(parentNode); - if (!materials.empty()) - { - xmlNode* bindMaterialNode = AddChild(instanceNode, DAE_BINDMATERIAL_ELEMENT); - xmlNode* techniqueCommonNode = AddChild(bindMaterialNode, DAE_TECHNIQUE_COMMON_ELEMENT); - for (FCDMaterialInstanceList::const_iterator itM = materials.begin(); itM != materials.end(); ++itM) - { - (*itM)->WriteToXML(techniqueCommonNode); - } - } - return instanceNode; -} + +// Write out the instantiation information to the xml node tree +xmlNode* FCDGeometryInstance::WriteToXML(xmlNode* parentNode) const +{ + xmlNode* instanceNode = FCDEntityInstance::WriteToXML(parentNode); + if (!materials.empty()) + { + xmlNode* bindMaterialNode = AddChild(instanceNode, DAE_BINDMATERIAL_ELEMENT); + xmlNode* techniqueCommonNode = AddChild(bindMaterialNode, DAE_TECHNIQUE_COMMON_ELEMENT); + for (FCDMaterialInstanceList::const_iterator itM = materials.begin(); itM != materials.end(); ++itM) + { + (*itM)->WriteToXML(techniqueCommonNode); + } + } + return instanceNode; +} diff --git a/Extras/FCollada/FCDocument/FCDGeometryMesh.cpp b/Extras/FCollada/FCDocument/FCDGeometryMesh.cpp index d5892fbea..927921504 100644 --- a/Extras/FCollada/FCDocument/FCDGeometryMesh.cpp +++ b/Extras/FCollada/FCDocument/FCDGeometryMesh.cpp @@ -23,6 +23,7 @@ using namespace FUDaeWriter; FCDGeometryMesh::FCDGeometryMesh(FCDocument* document, FCDGeometry* _parent) : FCDObject(document, "FCDGeometryMesh") { + m_convex = false; parent = _parent; faceVertexCount = faceCount = holeCount = 0; isDoubleSided = true; @@ -232,7 +233,7 @@ FCDGeometryMesh* FCDGeometryMesh::Clone(FloatList& newPositions, uint32 newPosit FUStatus FCDGeometryMesh::LoadFromXML(xmlNode* meshNode) { FUStatus status; - + // Read in the data sources xmlNodeList sourceDataNodes; FindChildrenByType(meshNode, DAE_SOURCE_ELEMENT, sourceDataNodes); diff --git a/Extras/FCollada/FCDocument/FCDGeometryMesh.h b/Extras/FCollada/FCDocument/FCDGeometryMesh.h index eedbd5035..15a0b49cc 100644 --- a/Extras/FCollada/FCDocument/FCDGeometryMesh.h +++ b/Extras/FCollada/FCDocument/FCDGeometryMesh.h @@ -204,6 +204,8 @@ public: @param parentNode The COLLADA XML parent node in which to insert the geometric mesh. @return The created \ element XML tree node. */ xmlNode* WriteToXML(xmlNode* parentNode) const; + + bool m_convex; }; #endif // _FCD_GEOMETRY_MESH_H_ diff --git a/analyticalGeomPhysicsTest.dae b/analyticalGeomPhysicsTest.dae index 72ac1909c..b6acdfe7a 100644 --- a/analyticalGeomPhysicsTest.dae +++ b/analyticalGeomPhysicsTest.dae @@ -366,11 +366,6 @@ dereferenceXRefs=0;cameraXFov=0;cameraYFov=1 0.500000 0.500000 0.736465 - - - 0.500000 0.500000 0.500000 - - @@ -382,11 +377,6 @@ dereferenceXRefs=0;cameraXFov=0;cameraYFov=1 1.000000 - - - 1.000000 - - diff --git a/colladaphysics_spherebox.dae b/colladaphysics_spherebox.dae index ac0bf39ab..3a0705cf8 100644 --- a/colladaphysics_spherebox.dae +++ b/colladaphysics_spherebox.dae @@ -555,7 +555,7 @@ - 1 1 1 + 1 1 1 true @@ -595,6 +595,10 @@ + + + 0 0 -9.810000 + diff --git a/msvc/8/appColladaDemo.vcproj b/msvc/8/appColladaDemo.vcproj index 3db7faebe..1240771c3 100644 --- a/msvc/8/appColladaDemo.vcproj +++ b/msvc/8/appColladaDemo.vcproj @@ -1,178 +1,244 @@ - + + > + Name="Win32" + /> + + + > + + + + + + SuppressStartupBanner="true" + Detect64BitPortabilityProblems="true" + DebugInformationFormat="3" + CompileAs="0" + /> - - - - - - + Name="VCManagedResourceCompilerTool" + /> + /> + Name="VCPreLinkEventTool" + /> + Name="VCLinkerTool" + IgnoreImportLibrary="true" + AdditionalOptions=" " + AdditionalDependencies="glut32.lib" + OutputFile="..\..\ColladaDemo.exe" + LinkIncremental="1" + SuppressStartupBanner="true" + AdditionalLibraryDirectories="..\..\Glut" + IgnoreDefaultLibraryNames="LIBC,LIBCD,LIBCMT,LIBCMTD" + GenerateDebugInformation="true" + ProgramDatabaseFile="..\..\out\release8\build\appColladaDemo\ColladaDemo.pdb" + SubSystem="1" + OptimizeReferences="2" + EnableCOMDATFolding="2" + TargetMachine="1" + /> + + + + + + + + + ATLMinimizesCRunTimeLibraryUsage="false" + CharacterSet="2" + > + + + + + + SuppressStartupBanner="true" + Detect64BitPortabilityProblems="true" + DebugInformationFormat="4" + CompileAs="0" + /> - - - - - - + Name="VCManagedResourceCompilerTool" + /> + /> + Name="VCPreLinkEventTool" + /> + Name="VCLinkerTool" + IgnoreImportLibrary="true" + AdditionalOptions=" " + AdditionalDependencies="glut32.lib" + OutputFile="..\..\ColladaDemo.exe" + LinkIncremental="2" + SuppressStartupBanner="true" + AdditionalLibraryDirectories="..\..\Glut" + IgnoreDefaultLibraryNames="LIBC,LIBCD,LIBCMT,LIBCMTD,MSVCRT" + GenerateDebugInformation="true" + ProgramDatabaseFile="..\..\out\debug8\build\appColladaDemo\ColladaDemo.pdb" + SubSystem="1" + TargetMachine="1" + /> + + + + + + + + + + + > + RelativePath="..\..\Demos\ColladaDemo\ColladaDemo.cpp" + > + > + RelativePath="..\..\msvc\appColladaDemo.rc" + > diff --git a/msvc/8/wksbullet.sln b/msvc/8/wksbullet.sln index 7f1422d7c..4b6c38b5b 100644 --- a/msvc/8/wksbullet.sln +++ b/msvc/8/wksbullet.sln @@ -1,36 +1,191 @@ Microsoft Visual Studio Solution File, Format Version 9.00 -# Visual C++ Express 2005 +# Visual Studio 2005 Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appBasicSample", "appBasicSample.vcproj", "{A584DCA6-74CD-02E3-E473-0D9990CD9A84}" + ProjectSection(ProjectDependencies) = postProject + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appCcdPhysicsDemo", "appCcdPhysicsDemo.vcproj", "{7284F809-AF30-6315-88C6-86F1C0798760}" + ProjectSection(ProjectDependencies) = postProject + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {7C428E76-9271-6284-20F0-9B38ED6931E3} = {7C428E76-9271-6284-20F0-9B38ED6931E3} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appColladaDemo", "appColladaDemo.vcproj", "{D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}" + ProjectSection(ProjectDependencies) = postProject + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC} = {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC} + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {7C428E76-9271-6284-20F0-9B38ED6931E3} = {7C428E76-9271-6284-20F0-9B38ED6931E3} + {5160A878-73A5-41CA-B8D5-C3D560DD1D58} = {5160A878-73A5-41CA-B8D5-C3D560DD1D58} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5} = {3D872CA6-782B-46C9-A336-1B18C0A4FBD5} + {FF956BB3-F377-43A8-AB31-633299BDF6C6} = {FF956BB3-F377-43A8-AB31-633299BDF6C6} + {D7F466F4-2AEA-4648-BE09-024C887BC157} = {D7F466F4-2AEA-4648-BE09-024C887BC157} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appCollisionDemo", "appCollisionDemo.vcproj", "{E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}" + ProjectSection(ProjectDependencies) = postProject + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {7C428E76-9271-6284-20F0-9B38ED6931E3} = {7C428E76-9271-6284-20F0-9B38ED6931E3} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appCollisionInterfaceDemo", "appCollisionInterfaceDemo.vcproj", "{F38629D2-EEB2-1A09-FB82-52B8A8DE759B}" + ProjectSection(ProjectDependencies) = postProject + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {7C428E76-9271-6284-20F0-9B38ED6931E3} = {7C428E76-9271-6284-20F0-9B38ED6931E3} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appConcaveDemo", "appConcaveDemo.vcproj", "{B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}" + ProjectSection(ProjectDependencies) = postProject + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {7C428E76-9271-6284-20F0-9B38ED6931E3} = {7C428E76-9271-6284-20F0-9B38ED6931E3} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appConstraintDemo", "appConstraintDemo.vcproj", "{DAA547D0-0166-C085-0F93-B88CAB800F97}" + ProjectSection(ProjectDependencies) = postProject + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {7C428E76-9271-6284-20F0-9B38ED6931E3} = {7C428E76-9271-6284-20F0-9B38ED6931E3} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appContinuousConvexCollision", "appContinuousConvexCollision.vcproj", "{801CB6D4-A45C-C9D2-B176-9711A74B9164}" + ProjectSection(ProjectDependencies) = postProject + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {7C428E76-9271-6284-20F0-9B38ED6931E3} = {7C428E76-9271-6284-20F0-9B38ED6931E3} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appConvexDecompositionDemo", "appConvexDecompositionDemo.vcproj", "{69C821C7-1E18-D894-068D-C55E063F4859}" + ProjectSection(ProjectDependencies) = postProject + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3} = {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3} + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {7C428E76-9271-6284-20F0-9B38ED6931E3} = {7C428E76-9271-6284-20F0-9B38ED6931E3} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appEPAPenDepthDemo", "appEPAPenDepthDemo.vcproj", "{1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}" + ProjectSection(ProjectDependencies) = postProject + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {7C428E76-9271-6284-20F0-9B38ED6931E3} = {7C428E76-9271-6284-20F0-9B38ED6931E3} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appGjkConvexCastDemo", "appGjkConvexCastDemo.vcproj", "{780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}" + ProjectSection(ProjectDependencies) = postProject + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {7C428E76-9271-6284-20F0-9B38ED6931E3} = {7C428E76-9271-6284-20F0-9B38ED6931E3} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appRaytracer", "appRaytracer.vcproj", "{60F71B6A-F888-C449-EF49-268BB9F7C963}" + ProjectSection(ProjectDependencies) = postProject + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {7C428E76-9271-6284-20F0-9B38ED6931E3} = {7C428E76-9271-6284-20F0-9B38ED6931E3} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appSimplexDemo", "appSimplexDemo.vcproj", "{60A1DC9D-F837-3923-E9DE-A7925394A578}" + ProjectSection(ProjectDependencies) = postProject + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {7C428E76-9271-6284-20F0-9B38ED6931E3} = {7C428E76-9271-6284-20F0-9B38ED6931E3} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "grpall_bullet", "grpall_bullet.vcproj", "{6210A080-01C0-6D67-F1DB-669393175402}" + ProjectSection(ProjectDependencies) = postProject + {7284F809-AF30-6315-88C6-86F1C0798760} = {7284F809-AF30-6315-88C6-86F1C0798760} + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3} = {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3} + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9} = {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9} + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {60F71B6A-F888-C449-EF49-268BB9F7C963} = {60F71B6A-F888-C449-EF49-268BB9F7C963} + {7C428E76-9271-6284-20F0-9B38ED6931E3} = {7C428E76-9271-6284-20F0-9B38ED6931E3} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {60A1DC9D-F837-3923-E9DE-A7925394A578} = {60A1DC9D-F837-3923-E9DE-A7925394A578} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + {A584DCA6-74CD-02E3-E473-0D9990CD9A84} = {A584DCA6-74CD-02E3-E473-0D9990CD9A84} + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1} = {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1} + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3} = {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3} + {69C821C7-1E18-D894-068D-C55E063F4859} = {69C821C7-1E18-D894-068D-C55E063F4859} + {DAA547D0-0166-C085-0F93-B88CAB800F97} = {DAA547D0-0166-C085-0F93-B88CAB800F97} + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B} = {F38629D2-EEB2-1A09-FB82-52B8A8DE759B} + {801CB6D4-A45C-C9D2-B176-9711A74B9164} = {801CB6D4-A45C-C9D2-B176-9711A74B9164} + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF} = {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF} + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3} = {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "grpapps_bullet", "grpapps_bullet.vcproj", "{9E59B16D-0924-409C-1611-DF2207A0053F}" + ProjectSection(ProjectDependencies) = postProject + {7284F809-AF30-6315-88C6-86F1C0798760} = {7284F809-AF30-6315-88C6-86F1C0798760} + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9} = {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9} + {60F71B6A-F888-C449-EF49-268BB9F7C963} = {60F71B6A-F888-C449-EF49-268BB9F7C963} + {60A1DC9D-F837-3923-E9DE-A7925394A578} = {60A1DC9D-F837-3923-E9DE-A7925394A578} + {A584DCA6-74CD-02E3-E473-0D9990CD9A84} = {A584DCA6-74CD-02E3-E473-0D9990CD9A84} + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1} = {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1} + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3} = {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3} + {69C821C7-1E18-D894-068D-C55E063F4859} = {69C821C7-1E18-D894-068D-C55E063F4859} + {DAA547D0-0166-C085-0F93-B88CAB800F97} = {DAA547D0-0166-C085-0F93-B88CAB800F97} + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B} = {F38629D2-EEB2-1A09-FB82-52B8A8DE759B} + {801CB6D4-A45C-C9D2-B176-9711A74B9164} = {801CB6D4-A45C-C9D2-B176-9711A74B9164} + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF} = {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF} + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3} = {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "grplibs_bullet", "grplibs_bullet.vcproj", "{DFAF0062-4CD7-9AB8-0683-A6026B326F56}" + ProjectSection(ProjectDependencies) = postProject + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3} = {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3} + {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} + {7C428E76-9271-6284-20F0-9B38ED6931E3} = {7C428E76-9271-6284-20F0-9B38ED6931E3} + {61BD1097-CF2E-B296-DAA9-73A6FE135319} = {61BD1097-CF2E-B296-DAA9-73A6FE135319} + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "libbullet", "libbullet.vcproj", "{90F5975E-550B-EEC8-9A8A-B8581D3FCF97}" EndProject @@ -46,227 +201,706 @@ Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "libbulletphysicsinterfaceco EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "libconvexdecomposition", "libconvexdecomposition.vcproj", "{8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}" EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "FCollada_vc8", "..\..\Extras\FCollada\FCollada_vc8.vcproj", "{FF956BB3-F377-43A8-AB31-633299BDF6C6}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "FColladaLib_vc8", "..\..\Extras\FCollada\FColladaLib_vc8.vcproj", "{5160A878-73A5-41CA-B8D5-C3D560DD1D58}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "FMath_vc8", "..\..\Extras\FCollada\FMath\FMath_vc8.vcproj", "{38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "FUtils_vc8", "..\..\Extras\FCollada\FUtils\FUtils_vc8.vcproj", "{3D872CA6-782B-46C9-A336-1B18C0A4FBD5}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "LibXML_vc8", "..\..\Extras\FCollada\LibXML\LibXML_vc8.vcproj", "{D7F466F4-2AEA-4648-BE09-024C887BC157}" +EndProject Global - GlobalSection(SolutionConfiguration) = preSolution - ConfigName.0 = Release - ConfigName.1 = Debug + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug DLL|Win32 = Debug DLL|Win32 + Debug MTD|Win32 = Debug MTD|Win32 + Debug Unicode DLL|Win32 = Debug Unicode DLL|Win32 + Debug Unicode MTD|Win32 = Debug Unicode MTD|Win32 + Debug Unicode|Win32 = Debug Unicode|Win32 + Debug|Win32 = Debug|Win32 + Release DLL|Win32 = Release DLL|Win32 + Release MTD|Win32 = Release MTD|Win32 + Release Unicode DLL|Win32 = Release Unicode DLL|Win32 + Release Unicode MTD|Win32 = Release Unicode MTD|Win32 + Release Unicode|Win32 = Release Unicode|Win32 + Release|Win32 = Release|Win32 EndGlobalSection - GlobalSection(ProjectDependencies) = postSolution - {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.0 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.1 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.2 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.3 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.4 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {7284F809-AF30-6315-88C6-86F1C0798760}.0 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {7284F809-AF30-6315-88C6-86F1C0798760}.1 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {7284F809-AF30-6315-88C6-86F1C0798760}.2 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {7284F809-AF30-6315-88C6-86F1C0798760}.3 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {7284F809-AF30-6315-88C6-86F1C0798760}.4 = {7C428E76-9271-6284-20F0-9B38ED6931E3} - {7284F809-AF30-6315-88C6-86F1C0798760}.5 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.0 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.1 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.2 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.3 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.4 = {7C428E76-9271-6284-20F0-9B38ED6931E3} - {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.5 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.0 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.1 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.2 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.3 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.4 = {7C428E76-9271-6284-20F0-9B38ED6931E3} - {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.5 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.0 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.1 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.2 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.3 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.4 = {7C428E76-9271-6284-20F0-9B38ED6931E3} - {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.5 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.0 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.1 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.2 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.3 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.4 = {7C428E76-9271-6284-20F0-9B38ED6931E3} - {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.5 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {DAA547D0-0166-C085-0F93-B88CAB800F97}.0 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {DAA547D0-0166-C085-0F93-B88CAB800F97}.1 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {DAA547D0-0166-C085-0F93-B88CAB800F97}.2 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {DAA547D0-0166-C085-0F93-B88CAB800F97}.3 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {DAA547D0-0166-C085-0F93-B88CAB800F97}.4 = {7C428E76-9271-6284-20F0-9B38ED6931E3} - {DAA547D0-0166-C085-0F93-B88CAB800F97}.5 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {801CB6D4-A45C-C9D2-B176-9711A74B9164}.0 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {801CB6D4-A45C-C9D2-B176-9711A74B9164}.1 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {801CB6D4-A45C-C9D2-B176-9711A74B9164}.2 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {801CB6D4-A45C-C9D2-B176-9711A74B9164}.3 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {801CB6D4-A45C-C9D2-B176-9711A74B9164}.4 = {7C428E76-9271-6284-20F0-9B38ED6931E3} - {801CB6D4-A45C-C9D2-B176-9711A74B9164}.5 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {69C821C7-1E18-D894-068D-C55E063F4859}.0 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {69C821C7-1E18-D894-068D-C55E063F4859}.1 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {69C821C7-1E18-D894-068D-C55E063F4859}.2 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {69C821C7-1E18-D894-068D-C55E063F4859}.3 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {69C821C7-1E18-D894-068D-C55E063F4859}.4 = {7C428E76-9271-6284-20F0-9B38ED6931E3} - {69C821C7-1E18-D894-068D-C55E063F4859}.5 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {69C821C7-1E18-D894-068D-C55E063F4859}.6 = {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3} - {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.0 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.1 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.2 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.3 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.4 = {7C428E76-9271-6284-20F0-9B38ED6931E3} - {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.5 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.0 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.1 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.2 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.3 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.4 = {7C428E76-9271-6284-20F0-9B38ED6931E3} - {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.5 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {60F71B6A-F888-C449-EF49-268BB9F7C963}.0 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {60F71B6A-F888-C449-EF49-268BB9F7C963}.1 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {60F71B6A-F888-C449-EF49-268BB9F7C963}.2 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {60F71B6A-F888-C449-EF49-268BB9F7C963}.3 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {60F71B6A-F888-C449-EF49-268BB9F7C963}.4 = {7C428E76-9271-6284-20F0-9B38ED6931E3} - {60F71B6A-F888-C449-EF49-268BB9F7C963}.5 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {60A1DC9D-F837-3923-E9DE-A7925394A578}.0 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {60A1DC9D-F837-3923-E9DE-A7925394A578}.1 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {60A1DC9D-F837-3923-E9DE-A7925394A578}.2 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {60A1DC9D-F837-3923-E9DE-A7925394A578}.3 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {60A1DC9D-F837-3923-E9DE-A7925394A578}.4 = {7C428E76-9271-6284-20F0-9B38ED6931E3} - {60A1DC9D-F837-3923-E9DE-A7925394A578}.5 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {6210A080-01C0-6D67-F1DB-669393175402}.0 = {A584DCA6-74CD-02E3-E473-0D9990CD9A84} - {6210A080-01C0-6D67-F1DB-669393175402}.1 = {7284F809-AF30-6315-88C6-86F1C0798760} - {6210A080-01C0-6D67-F1DB-669393175402}.2 = {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF} - {6210A080-01C0-6D67-F1DB-669393175402}.3 = {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9} - {6210A080-01C0-6D67-F1DB-669393175402}.4 = {F38629D2-EEB2-1A09-FB82-52B8A8DE759B} - {6210A080-01C0-6D67-F1DB-669393175402}.5 = {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3} - {6210A080-01C0-6D67-F1DB-669393175402}.6 = {DAA547D0-0166-C085-0F93-B88CAB800F97} - {6210A080-01C0-6D67-F1DB-669393175402}.7 = {801CB6D4-A45C-C9D2-B176-9711A74B9164} - {6210A080-01C0-6D67-F1DB-669393175402}.8 = {69C821C7-1E18-D894-068D-C55E063F4859} - {6210A080-01C0-6D67-F1DB-669393175402}.9 = {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3} - {6210A080-01C0-6D67-F1DB-669393175402}.10 = {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1} - {6210A080-01C0-6D67-F1DB-669393175402}.11 = {60F71B6A-F888-C449-EF49-268BB9F7C963} - {6210A080-01C0-6D67-F1DB-669393175402}.12 = {60A1DC9D-F837-3923-E9DE-A7925394A578} - {6210A080-01C0-6D67-F1DB-669393175402}.13 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {6210A080-01C0-6D67-F1DB-669393175402}.14 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {6210A080-01C0-6D67-F1DB-669393175402}.15 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {6210A080-01C0-6D67-F1DB-669393175402}.16 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {6210A080-01C0-6D67-F1DB-669393175402}.17 = {7C428E76-9271-6284-20F0-9B38ED6931E3} - {6210A080-01C0-6D67-F1DB-669393175402}.18 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {6210A080-01C0-6D67-F1DB-669393175402}.19 = {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3} - {9E59B16D-0924-409C-1611-DF2207A0053F}.0 = {A584DCA6-74CD-02E3-E473-0D9990CD9A84} - {9E59B16D-0924-409C-1611-DF2207A0053F}.1 = {7284F809-AF30-6315-88C6-86F1C0798760} - {9E59B16D-0924-409C-1611-DF2207A0053F}.2 = {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF} - {9E59B16D-0924-409C-1611-DF2207A0053F}.3 = {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9} - {9E59B16D-0924-409C-1611-DF2207A0053F}.4 = {F38629D2-EEB2-1A09-FB82-52B8A8DE759B} - {9E59B16D-0924-409C-1611-DF2207A0053F}.5 = {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3} - {9E59B16D-0924-409C-1611-DF2207A0053F}.6 = {DAA547D0-0166-C085-0F93-B88CAB800F97} - {9E59B16D-0924-409C-1611-DF2207A0053F}.7 = {801CB6D4-A45C-C9D2-B176-9711A74B9164} - {9E59B16D-0924-409C-1611-DF2207A0053F}.8 = {69C821C7-1E18-D894-068D-C55E063F4859} - {9E59B16D-0924-409C-1611-DF2207A0053F}.9 = {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3} - {9E59B16D-0924-409C-1611-DF2207A0053F}.10 = {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1} - {9E59B16D-0924-409C-1611-DF2207A0053F}.11 = {60F71B6A-F888-C449-EF49-268BB9F7C963} - {9E59B16D-0924-409C-1611-DF2207A0053F}.12 = {60A1DC9D-F837-3923-E9DE-A7925394A578} - {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.0 = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} - {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.1 = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} - {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.2 = {61BD1097-CF2E-B296-DAA9-73A6FE135319} - {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.3 = {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A} - {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.4 = {7C428E76-9271-6284-20F0-9B38ED6931E3} - {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.5 = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.6 = {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3} + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Debug DLL|Win32.Build.0 = Debug|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Debug MTD|Win32.Build.0 = Debug|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Debug|Win32.ActiveCfg = Debug|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Debug|Win32.Build.0 = Debug|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Release DLL|Win32.ActiveCfg = Release|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Release DLL|Win32.Build.0 = Release|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Release MTD|Win32.ActiveCfg = Release|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Release MTD|Win32.Build.0 = Release|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Release Unicode|Win32.Build.0 = Release|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Release|Win32.ActiveCfg = Release|Win32 + {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Release|Win32.Build.0 = Release|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Debug DLL|Win32.Build.0 = Debug|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Debug MTD|Win32.Build.0 = Debug|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Debug|Win32.ActiveCfg = Debug|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Debug|Win32.Build.0 = Debug|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Release DLL|Win32.ActiveCfg = Release|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Release DLL|Win32.Build.0 = Release|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Release MTD|Win32.ActiveCfg = Release|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Release MTD|Win32.Build.0 = Release|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Release Unicode|Win32.Build.0 = Release|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Release|Win32.ActiveCfg = Release|Win32 + {7284F809-AF30-6315-88C6-86F1C0798760}.Release|Win32.Build.0 = Release|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Debug DLL|Win32.Build.0 = Debug|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Debug MTD|Win32.Build.0 = Debug|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Debug|Win32.ActiveCfg = Debug|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Debug|Win32.Build.0 = Debug|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Release DLL|Win32.ActiveCfg = Release|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Release DLL|Win32.Build.0 = Release|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Release MTD|Win32.ActiveCfg = Release|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Release MTD|Win32.Build.0 = Release|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Release Unicode|Win32.Build.0 = Release|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Release|Win32.ActiveCfg = Release|Win32 + {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Release|Win32.Build.0 = Release|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Debug DLL|Win32.Build.0 = Debug|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Debug MTD|Win32.Build.0 = Debug|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Debug|Win32.ActiveCfg = Debug|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Debug|Win32.Build.0 = Debug|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Release DLL|Win32.ActiveCfg = Release|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Release DLL|Win32.Build.0 = Release|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Release MTD|Win32.ActiveCfg = Release|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Release MTD|Win32.Build.0 = Release|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Release Unicode|Win32.Build.0 = Release|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Release|Win32.ActiveCfg = Release|Win32 + {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Release|Win32.Build.0 = Release|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Debug DLL|Win32.Build.0 = Debug|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Debug MTD|Win32.Build.0 = Debug|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Debug|Win32.ActiveCfg = Debug|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Debug|Win32.Build.0 = Debug|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Release DLL|Win32.ActiveCfg = Release|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Release DLL|Win32.Build.0 = Release|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Release MTD|Win32.ActiveCfg = Release|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Release MTD|Win32.Build.0 = Release|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Release Unicode|Win32.Build.0 = Release|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Release|Win32.ActiveCfg = Release|Win32 + {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Release|Win32.Build.0 = Release|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Debug DLL|Win32.Build.0 = Debug|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Debug MTD|Win32.Build.0 = Debug|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Debug|Win32.ActiveCfg = Debug|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Debug|Win32.Build.0 = Debug|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Release DLL|Win32.ActiveCfg = Release|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Release DLL|Win32.Build.0 = Release|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Release MTD|Win32.ActiveCfg = Release|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Release MTD|Win32.Build.0 = Release|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Release Unicode|Win32.Build.0 = Release|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Release|Win32.ActiveCfg = Release|Win32 + {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Release|Win32.Build.0 = Release|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Debug DLL|Win32.Build.0 = Debug|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Debug MTD|Win32.Build.0 = Debug|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Debug|Win32.ActiveCfg = Debug|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Debug|Win32.Build.0 = Debug|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Release DLL|Win32.ActiveCfg = Release|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Release DLL|Win32.Build.0 = Release|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Release MTD|Win32.ActiveCfg = Release|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Release MTD|Win32.Build.0 = Release|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Release Unicode|Win32.Build.0 = Release|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Release|Win32.ActiveCfg = Release|Win32 + {DAA547D0-0166-C085-0F93-B88CAB800F97}.Release|Win32.Build.0 = Release|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Debug DLL|Win32.Build.0 = Debug|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Debug MTD|Win32.Build.0 = Debug|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Debug|Win32.ActiveCfg = Debug|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Debug|Win32.Build.0 = Debug|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Release DLL|Win32.ActiveCfg = Release|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Release DLL|Win32.Build.0 = Release|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Release MTD|Win32.ActiveCfg = Release|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Release MTD|Win32.Build.0 = Release|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Release Unicode|Win32.Build.0 = Release|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Release|Win32.ActiveCfg = Release|Win32 + {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Release|Win32.Build.0 = Release|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Debug DLL|Win32.Build.0 = Debug|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Debug MTD|Win32.Build.0 = Debug|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Debug|Win32.ActiveCfg = Debug|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Debug|Win32.Build.0 = Debug|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Release DLL|Win32.ActiveCfg = Release|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Release DLL|Win32.Build.0 = Release|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Release MTD|Win32.ActiveCfg = Release|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Release MTD|Win32.Build.0 = Release|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Release Unicode|Win32.Build.0 = Release|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Release|Win32.ActiveCfg = Release|Win32 + {69C821C7-1E18-D894-068D-C55E063F4859}.Release|Win32.Build.0 = Release|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Debug DLL|Win32.Build.0 = Debug|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Debug MTD|Win32.Build.0 = Debug|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Debug|Win32.ActiveCfg = Debug|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Debug|Win32.Build.0 = Debug|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Release DLL|Win32.ActiveCfg = Release|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Release DLL|Win32.Build.0 = Release|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Release MTD|Win32.ActiveCfg = Release|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Release MTD|Win32.Build.0 = Release|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Release Unicode|Win32.Build.0 = Release|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Release|Win32.ActiveCfg = Release|Win32 + {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Release|Win32.Build.0 = Release|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Debug DLL|Win32.Build.0 = Debug|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Debug MTD|Win32.Build.0 = Debug|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Debug|Win32.ActiveCfg = Debug|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Debug|Win32.Build.0 = Debug|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Release DLL|Win32.ActiveCfg = Release|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Release DLL|Win32.Build.0 = Release|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Release MTD|Win32.ActiveCfg = Release|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Release MTD|Win32.Build.0 = Release|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Release Unicode|Win32.Build.0 = Release|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Release|Win32.ActiveCfg = Release|Win32 + {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Release|Win32.Build.0 = Release|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Debug DLL|Win32.Build.0 = Debug|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Debug MTD|Win32.Build.0 = Debug|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Debug|Win32.ActiveCfg = Debug|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Debug|Win32.Build.0 = Debug|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Release DLL|Win32.ActiveCfg = Release|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Release DLL|Win32.Build.0 = Release|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Release MTD|Win32.ActiveCfg = Release|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Release MTD|Win32.Build.0 = Release|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Release Unicode|Win32.Build.0 = Release|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Release|Win32.ActiveCfg = Release|Win32 + {60F71B6A-F888-C449-EF49-268BB9F7C963}.Release|Win32.Build.0 = Release|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Debug DLL|Win32.Build.0 = Debug|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Debug MTD|Win32.Build.0 = Debug|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Debug|Win32.ActiveCfg = Debug|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Debug|Win32.Build.0 = Debug|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Release DLL|Win32.ActiveCfg = Release|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Release DLL|Win32.Build.0 = Release|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Release MTD|Win32.ActiveCfg = Release|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Release MTD|Win32.Build.0 = Release|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Release Unicode|Win32.Build.0 = Release|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Release|Win32.ActiveCfg = Release|Win32 + {60A1DC9D-F837-3923-E9DE-A7925394A578}.Release|Win32.Build.0 = Release|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Debug DLL|Win32.Build.0 = Debug|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Debug MTD|Win32.Build.0 = Debug|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Debug|Win32.ActiveCfg = Debug|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Debug|Win32.Build.0 = Debug|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Release DLL|Win32.ActiveCfg = Release|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Release DLL|Win32.Build.0 = Release|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Release MTD|Win32.ActiveCfg = Release|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Release MTD|Win32.Build.0 = Release|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Release Unicode|Win32.Build.0 = Release|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Release|Win32.ActiveCfg = Release|Win32 + {6210A080-01C0-6D67-F1DB-669393175402}.Release|Win32.Build.0 = Release|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Debug DLL|Win32.Build.0 = Debug|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Debug MTD|Win32.Build.0 = Debug|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Debug|Win32.ActiveCfg = Debug|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Debug|Win32.Build.0 = Debug|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Release DLL|Win32.ActiveCfg = Release|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Release DLL|Win32.Build.0 = Release|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Release MTD|Win32.ActiveCfg = Release|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Release MTD|Win32.Build.0 = Release|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Release Unicode|Win32.Build.0 = Release|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Release|Win32.ActiveCfg = Release|Win32 + {9E59B16D-0924-409C-1611-DF2207A0053F}.Release|Win32.Build.0 = Release|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Debug DLL|Win32.Build.0 = Debug|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Debug MTD|Win32.Build.0 = Debug|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Debug|Win32.ActiveCfg = Debug|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Debug|Win32.Build.0 = Debug|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Release DLL|Win32.ActiveCfg = Release|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Release DLL|Win32.Build.0 = Release|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Release MTD|Win32.ActiveCfg = Release|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Release MTD|Win32.Build.0 = Release|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Release Unicode|Win32.Build.0 = Release|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Release|Win32.ActiveCfg = Release|Win32 + {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Release|Win32.Build.0 = Release|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Debug DLL|Win32.Build.0 = Debug|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Debug MTD|Win32.Build.0 = Debug|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Debug|Win32.ActiveCfg = Debug|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Debug|Win32.Build.0 = Debug|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Release DLL|Win32.ActiveCfg = Release|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Release DLL|Win32.Build.0 = Release|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Release MTD|Win32.ActiveCfg = Release|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Release MTD|Win32.Build.0 = Release|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Release Unicode|Win32.Build.0 = Release|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Release|Win32.ActiveCfg = Release|Win32 + {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Release|Win32.Build.0 = Release|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Debug DLL|Win32.Build.0 = Debug|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Debug MTD|Win32.Build.0 = Debug|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Debug|Win32.ActiveCfg = Debug|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Debug|Win32.Build.0 = Debug|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Release DLL|Win32.ActiveCfg = Release|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Release DLL|Win32.Build.0 = Release|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Release MTD|Win32.ActiveCfg = Release|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Release MTD|Win32.Build.0 = Release|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Release Unicode|Win32.Build.0 = Release|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Release|Win32.ActiveCfg = Release|Win32 + {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Release|Win32.Build.0 = Release|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Debug DLL|Win32.Build.0 = Debug|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Debug MTD|Win32.Build.0 = Debug|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Debug|Win32.ActiveCfg = Debug|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Debug|Win32.Build.0 = Debug|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Release DLL|Win32.ActiveCfg = Release|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Release DLL|Win32.Build.0 = Release|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Release MTD|Win32.ActiveCfg = Release|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Release MTD|Win32.Build.0 = Release|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Release Unicode|Win32.Build.0 = Release|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Release|Win32.ActiveCfg = Release|Win32 + {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Release|Win32.Build.0 = Release|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Debug DLL|Win32.Build.0 = Debug|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Debug MTD|Win32.Build.0 = Debug|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Debug|Win32.ActiveCfg = Debug|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Debug|Win32.Build.0 = Debug|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Release DLL|Win32.ActiveCfg = Release|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Release DLL|Win32.Build.0 = Release|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Release MTD|Win32.ActiveCfg = Release|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Release MTD|Win32.Build.0 = Release|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Release Unicode|Win32.Build.0 = Release|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Release|Win32.ActiveCfg = Release|Win32 + {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Release|Win32.Build.0 = Release|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Debug DLL|Win32.Build.0 = Debug|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Debug MTD|Win32.Build.0 = Debug|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Debug|Win32.ActiveCfg = Debug|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Debug|Win32.Build.0 = Debug|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Release DLL|Win32.ActiveCfg = Release|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Release DLL|Win32.Build.0 = Release|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Release MTD|Win32.ActiveCfg = Release|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Release MTD|Win32.Build.0 = Release|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Release Unicode|Win32.Build.0 = Release|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Release|Win32.ActiveCfg = Release|Win32 + {7C428E76-9271-6284-20F0-9B38ED6931E3}.Release|Win32.Build.0 = Release|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Debug DLL|Win32.Build.0 = Debug|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Debug MTD|Win32.Build.0 = Debug|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Debug|Win32.ActiveCfg = Debug|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Debug|Win32.Build.0 = Debug|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Release DLL|Win32.ActiveCfg = Release|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Release DLL|Win32.Build.0 = Release|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Release MTD|Win32.ActiveCfg = Release|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Release MTD|Win32.Build.0 = Release|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Release Unicode|Win32.Build.0 = Release|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Release|Win32.ActiveCfg = Release|Win32 + {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Release|Win32.Build.0 = Release|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Debug DLL|Win32.ActiveCfg = Debug|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Debug DLL|Win32.Build.0 = Debug|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Debug MTD|Win32.ActiveCfg = Debug|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Debug MTD|Win32.Build.0 = Debug|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Debug Unicode DLL|Win32.ActiveCfg = Debug|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Debug Unicode DLL|Win32.Build.0 = Debug|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Debug Unicode MTD|Win32.ActiveCfg = Debug|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Debug Unicode MTD|Win32.Build.0 = Debug|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Debug Unicode|Win32.ActiveCfg = Debug|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Debug Unicode|Win32.Build.0 = Debug|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Debug|Win32.ActiveCfg = Debug|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Debug|Win32.Build.0 = Debug|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Release DLL|Win32.ActiveCfg = Release|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Release DLL|Win32.Build.0 = Release|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Release MTD|Win32.ActiveCfg = Release|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Release MTD|Win32.Build.0 = Release|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Release Unicode DLL|Win32.ActiveCfg = Release|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Release Unicode DLL|Win32.Build.0 = Release|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Release Unicode MTD|Win32.ActiveCfg = Release|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Release Unicode MTD|Win32.Build.0 = Release|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Release Unicode|Win32.ActiveCfg = Release|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Release Unicode|Win32.Build.0 = Release|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Release|Win32.ActiveCfg = Release|Win32 + {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Release|Win32.Build.0 = Release|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Debug DLL|Win32.ActiveCfg = Debug DLL|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Debug DLL|Win32.Build.0 = Debug DLL|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Debug MTD|Win32.ActiveCfg = Debug Unicode MTD|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Debug MTD|Win32.Build.0 = Debug Unicode MTD|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Debug Unicode DLL|Win32.ActiveCfg = Debug Unicode DLL|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Debug Unicode DLL|Win32.Build.0 = Debug Unicode DLL|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Debug Unicode MTD|Win32.ActiveCfg = Debug Unicode MTD|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Debug Unicode MTD|Win32.Build.0 = Debug Unicode MTD|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Debug Unicode|Win32.ActiveCfg = Debug Unicode|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Debug Unicode|Win32.Build.0 = Debug Unicode|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Debug|Win32.ActiveCfg = Debug|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Debug|Win32.Build.0 = Debug|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Release DLL|Win32.ActiveCfg = Release DLL|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Release DLL|Win32.Build.0 = Release DLL|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Release MTD|Win32.ActiveCfg = Release Unicode MTD|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Release MTD|Win32.Build.0 = Release Unicode MTD|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Release Unicode DLL|Win32.ActiveCfg = Release Unicode DLL|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Release Unicode DLL|Win32.Build.0 = Release Unicode DLL|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Release Unicode MTD|Win32.ActiveCfg = Release Unicode MTD|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Release Unicode MTD|Win32.Build.0 = Release Unicode MTD|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Release Unicode|Win32.ActiveCfg = Release Unicode|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Release Unicode|Win32.Build.0 = Release Unicode|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Release|Win32.ActiveCfg = Release|Win32 + {FF956BB3-F377-43A8-AB31-633299BDF6C6}.Release|Win32.Build.0 = Release|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Debug DLL|Win32.ActiveCfg = Debug DLL|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Debug DLL|Win32.Build.0 = Debug DLL|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Debug MTD|Win32.ActiveCfg = Debug Unicode MTD|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Debug MTD|Win32.Build.0 = Debug Unicode MTD|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Debug Unicode DLL|Win32.ActiveCfg = Debug Unicode DLL|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Debug Unicode DLL|Win32.Build.0 = Debug Unicode DLL|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Debug Unicode MTD|Win32.ActiveCfg = Debug Unicode MTD|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Debug Unicode MTD|Win32.Build.0 = Debug Unicode MTD|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Debug Unicode|Win32.ActiveCfg = Debug Unicode|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Debug Unicode|Win32.Build.0 = Debug Unicode|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Debug|Win32.ActiveCfg = Debug|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Debug|Win32.Build.0 = Debug|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Release DLL|Win32.ActiveCfg = Release DLL|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Release DLL|Win32.Build.0 = Release DLL|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Release MTD|Win32.ActiveCfg = Release Unicode MTD|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Release MTD|Win32.Build.0 = Release Unicode MTD|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Release Unicode DLL|Win32.ActiveCfg = Release Unicode DLL|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Release Unicode DLL|Win32.Build.0 = Release Unicode DLL|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Release Unicode MTD|Win32.ActiveCfg = Release Unicode MTD|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Release Unicode MTD|Win32.Build.0 = Release Unicode MTD|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Release Unicode|Win32.ActiveCfg = Release Unicode|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Release Unicode|Win32.Build.0 = Release Unicode|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Release|Win32.ActiveCfg = Release|Win32 + {5160A878-73A5-41CA-B8D5-C3D560DD1D58}.Release|Win32.Build.0 = Release|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Debug DLL|Win32.ActiveCfg = Debug DLL|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Debug DLL|Win32.Build.0 = Debug DLL|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Debug MTD|Win32.ActiveCfg = Debug Unicode MTD|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Debug MTD|Win32.Build.0 = Debug Unicode MTD|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Debug Unicode DLL|Win32.ActiveCfg = Debug Unicode DLL|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Debug Unicode DLL|Win32.Build.0 = Debug Unicode DLL|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Debug Unicode MTD|Win32.ActiveCfg = Debug Unicode MTD|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Debug Unicode MTD|Win32.Build.0 = Debug Unicode MTD|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Debug Unicode|Win32.ActiveCfg = Debug Unicode|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Debug Unicode|Win32.Build.0 = Debug Unicode|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Debug|Win32.ActiveCfg = Debug|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Debug|Win32.Build.0 = Debug|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Release DLL|Win32.ActiveCfg = Release DLL|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Release DLL|Win32.Build.0 = Release DLL|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Release MTD|Win32.ActiveCfg = Release Unicode MTD|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Release MTD|Win32.Build.0 = Release Unicode MTD|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Release Unicode DLL|Win32.ActiveCfg = Release Unicode DLL|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Release Unicode DLL|Win32.Build.0 = Release Unicode DLL|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Release Unicode MTD|Win32.ActiveCfg = Release Unicode MTD|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Release Unicode MTD|Win32.Build.0 = Release Unicode MTD|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Release Unicode|Win32.ActiveCfg = Release Unicode|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Release Unicode|Win32.Build.0 = Release Unicode|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Release|Win32.ActiveCfg = Release|Win32 + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}.Release|Win32.Build.0 = Release|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Debug DLL|Win32.ActiveCfg = Debug DLL|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Debug DLL|Win32.Build.0 = Debug DLL|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Debug MTD|Win32.ActiveCfg = Debug Unicode MTD|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Debug MTD|Win32.Build.0 = Debug Unicode MTD|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Debug Unicode DLL|Win32.ActiveCfg = Debug Unicode DLL|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Debug Unicode DLL|Win32.Build.0 = Debug Unicode DLL|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Debug Unicode MTD|Win32.ActiveCfg = Debug Unicode MTD|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Debug Unicode MTD|Win32.Build.0 = Debug Unicode MTD|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Debug Unicode|Win32.ActiveCfg = Debug Unicode|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Debug Unicode|Win32.Build.0 = Debug Unicode|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Debug|Win32.ActiveCfg = Debug|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Debug|Win32.Build.0 = Debug|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Release DLL|Win32.ActiveCfg = Release DLL|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Release DLL|Win32.Build.0 = Release DLL|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Release MTD|Win32.ActiveCfg = Release Unicode MTD|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Release MTD|Win32.Build.0 = Release Unicode MTD|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Release Unicode DLL|Win32.ActiveCfg = Release Unicode DLL|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Release Unicode DLL|Win32.Build.0 = Release Unicode DLL|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Release Unicode MTD|Win32.ActiveCfg = Release Unicode MTD|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Release Unicode MTD|Win32.Build.0 = Release Unicode MTD|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Release Unicode|Win32.ActiveCfg = Release Unicode|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Release Unicode|Win32.Build.0 = Release Unicode|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Release|Win32.ActiveCfg = Release|Win32 + {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}.Release|Win32.Build.0 = Release|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Debug DLL|Win32.ActiveCfg = Debug DLL|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Debug DLL|Win32.Build.0 = Debug DLL|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Debug MTD|Win32.ActiveCfg = Debug MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Debug MTD|Win32.Build.0 = Debug MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Debug Unicode DLL|Win32.ActiveCfg = Debug MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Debug Unicode DLL|Win32.Build.0 = Debug MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Debug Unicode MTD|Win32.ActiveCfg = Debug MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Debug Unicode MTD|Win32.Build.0 = Debug MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Debug Unicode|Win32.ActiveCfg = Debug MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Debug Unicode|Win32.Build.0 = Debug MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Debug|Win32.ActiveCfg = Debug|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Debug|Win32.Build.0 = Debug|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Release DLL|Win32.ActiveCfg = Release DLL|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Release DLL|Win32.Build.0 = Release DLL|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Release MTD|Win32.ActiveCfg = Release MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Release MTD|Win32.Build.0 = Release MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Release Unicode DLL|Win32.ActiveCfg = Release MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Release Unicode DLL|Win32.Build.0 = Release MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Release Unicode MTD|Win32.ActiveCfg = Release MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Release Unicode MTD|Win32.Build.0 = Release MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Release Unicode|Win32.ActiveCfg = Release MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Release Unicode|Win32.Build.0 = Release MTD|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Release|Win32.ActiveCfg = Release|Win32 + {D7F466F4-2AEA-4648-BE09-024C887BC157}.Release|Win32.Build.0 = Release|Win32 EndGlobalSection - GlobalSection(ProjectConfiguration) = postSolution - {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Release.ActiveCfg = Release|Win32 - {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Release.Build.0 = Release|Win32 - {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Debug.ActiveCfg = Debug|Win32 - {A584DCA6-74CD-02E3-E473-0D9990CD9A84}.Debug.Build.0 = Debug|Win32 - {7284F809-AF30-6315-88C6-86F1C0798760}.Release.ActiveCfg = Release|Win32 - {7284F809-AF30-6315-88C6-86F1C0798760}.Release.Build.0 = Release|Win32 - {7284F809-AF30-6315-88C6-86F1C0798760}.Debug.ActiveCfg = Debug|Win32 - {7284F809-AF30-6315-88C6-86F1C0798760}.Debug.Build.0 = Debug|Win32 - {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Release.ActiveCfg = Release|Win32 - {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Release.Build.0 = Release|Win32 - {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Debug.ActiveCfg = Debug|Win32 - {D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}.Debug.Build.0 = Debug|Win32 - {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Release.ActiveCfg = Release|Win32 - {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Release.Build.0 = Release|Win32 - {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Debug.ActiveCfg = Debug|Win32 - {E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}.Debug.Build.0 = Debug|Win32 - {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Release.ActiveCfg = Release|Win32 - {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Release.Build.0 = Release|Win32 - {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Debug.ActiveCfg = Debug|Win32 - {F38629D2-EEB2-1A09-FB82-52B8A8DE759B}.Debug.Build.0 = Debug|Win32 - {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Release.ActiveCfg = Release|Win32 - {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Release.Build.0 = Release|Win32 - {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Debug.ActiveCfg = Debug|Win32 - {B94C19C6-F6E7-2F60-56E2-E0BA681B74B3}.Debug.Build.0 = Debug|Win32 - {DAA547D0-0166-C085-0F93-B88CAB800F97}.Release.ActiveCfg = Release|Win32 - {DAA547D0-0166-C085-0F93-B88CAB800F97}.Release.Build.0 = Release|Win32 - {DAA547D0-0166-C085-0F93-B88CAB800F97}.Debug.ActiveCfg = Debug|Win32 - {DAA547D0-0166-C085-0F93-B88CAB800F97}.Debug.Build.0 = Debug|Win32 - {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Release.ActiveCfg = Release|Win32 - {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Release.Build.0 = Release|Win32 - {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Debug.ActiveCfg = Debug|Win32 - {801CB6D4-A45C-C9D2-B176-9711A74B9164}.Debug.Build.0 = Debug|Win32 - {69C821C7-1E18-D894-068D-C55E063F4859}.Release.ActiveCfg = Release|Win32 - {69C821C7-1E18-D894-068D-C55E063F4859}.Release.Build.0 = Release|Win32 - {69C821C7-1E18-D894-068D-C55E063F4859}.Debug.ActiveCfg = Debug|Win32 - {69C821C7-1E18-D894-068D-C55E063F4859}.Debug.Build.0 = Debug|Win32 - {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Release.ActiveCfg = Release|Win32 - {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Release.Build.0 = Release|Win32 - {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Debug.ActiveCfg = Debug|Win32 - {1125C7F3-9E0D-27B1-C97B-CDAB5CE161A3}.Debug.Build.0 = Debug|Win32 - {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Release.ActiveCfg = Release|Win32 - {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Release.Build.0 = Release|Win32 - {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Debug.ActiveCfg = Debug|Win32 - {780752A8-6322-5D3E-EF42-D0FD8BF9CEA1}.Debug.Build.0 = Debug|Win32 - {60F71B6A-F888-C449-EF49-268BB9F7C963}.Release.ActiveCfg = Release|Win32 - {60F71B6A-F888-C449-EF49-268BB9F7C963}.Release.Build.0 = Release|Win32 - {60F71B6A-F888-C449-EF49-268BB9F7C963}.Debug.ActiveCfg = Debug|Win32 - {60F71B6A-F888-C449-EF49-268BB9F7C963}.Debug.Build.0 = Debug|Win32 - {60A1DC9D-F837-3923-E9DE-A7925394A578}.Release.ActiveCfg = Release|Win32 - {60A1DC9D-F837-3923-E9DE-A7925394A578}.Release.Build.0 = Release|Win32 - {60A1DC9D-F837-3923-E9DE-A7925394A578}.Debug.ActiveCfg = Debug|Win32 - {60A1DC9D-F837-3923-E9DE-A7925394A578}.Debug.Build.0 = Debug|Win32 - {6210A080-01C0-6D67-F1DB-669393175402}.Release.ActiveCfg = Release|Win32 - {6210A080-01C0-6D67-F1DB-669393175402}.Release.Build.0 = Release|Win32 - {6210A080-01C0-6D67-F1DB-669393175402}.Debug.ActiveCfg = Debug|Win32 - {6210A080-01C0-6D67-F1DB-669393175402}.Debug.Build.0 = Debug|Win32 - {9E59B16D-0924-409C-1611-DF2207A0053F}.Release.ActiveCfg = Release|Win32 - {9E59B16D-0924-409C-1611-DF2207A0053F}.Release.Build.0 = Release|Win32 - {9E59B16D-0924-409C-1611-DF2207A0053F}.Debug.ActiveCfg = Debug|Win32 - {9E59B16D-0924-409C-1611-DF2207A0053F}.Debug.Build.0 = Debug|Win32 - {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Release.ActiveCfg = Release|Win32 - {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Release.Build.0 = Release|Win32 - {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Debug.ActiveCfg = Debug|Win32 - {DFAF0062-4CD7-9AB8-0683-A6026B326F56}.Debug.Build.0 = Debug|Win32 - {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Release.ActiveCfg = Release|Win32 - {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Release.Build.0 = Release|Win32 - {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Debug.ActiveCfg = Debug|Win32 - {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}.Debug.Build.0 = Debug|Win32 - {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Release.ActiveCfg = Release|Win32 - {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Release.Build.0 = Release|Win32 - {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Debug.ActiveCfg = Debug|Win32 - {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}.Debug.Build.0 = Debug|Win32 - {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Release.ActiveCfg = Release|Win32 - {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Release.Build.0 = Release|Win32 - {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Debug.ActiveCfg = Debug|Win32 - {61BD1097-CF2E-B296-DAA9-73A6FE135319}.Debug.Build.0 = Debug|Win32 - {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Release.ActiveCfg = Release|Win32 - {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Release.Build.0 = Release|Win32 - {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Debug.ActiveCfg = Debug|Win32 - {7D6E339F-9C2C-31DA-FDB0-5EE50973CF2A}.Debug.Build.0 = Debug|Win32 - {7C428E76-9271-6284-20F0-9B38ED6931E3}.Release.ActiveCfg = Release|Win32 - {7C428E76-9271-6284-20F0-9B38ED6931E3}.Release.Build.0 = Release|Win32 - {7C428E76-9271-6284-20F0-9B38ED6931E3}.Debug.ActiveCfg = Debug|Win32 - {7C428E76-9271-6284-20F0-9B38ED6931E3}.Debug.Build.0 = Debug|Win32 - {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Release.ActiveCfg = Release|Win32 - {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Release.Build.0 = Release|Win32 - {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Debug.ActiveCfg = Debug|Win32 - {85BCCE3E-992B-B6D7-28F6-CF0A12680822}.Debug.Build.0 = Debug|Win32 - {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Release.ActiveCfg = Release|Win32 - {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Release.Build.0 = Release|Win32 - {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Debug.ActiveCfg = Debug|Win32 - {8050F819-5B5B-1504-BC6D-7F2B4C6C85F3}.Debug.Build.0 = Debug|Win32 - EndGlobalSection - GlobalSection(ExtensibilityGlobals) = postSolution - EndGlobalSection - GlobalSection(ExtensibilityAddIns) = postSolution + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE EndGlobalSection EndGlobal