From f743269af9451ce5f95c6a5eb947dc3bc40a6125 Mon Sep 17 00:00:00 2001 From: ejcoumans Date: Sat, 3 Jun 2006 21:09:14 +0000 Subject: [PATCH] Added Generic 6 DOF Constraint skeleton --- .../Generic6DofConstraint.cpp | 175 ++++++++++ .../ConstraintSolver/Generic6DofConstraint.h | 68 ++++ Demos/ConstraintDemo/ConstraintDemo.cpp | 11 +- .../CcdPhysics/CcdPhysicsEnvironment.cpp | 31 ++ .../Common/PHY_DynamicTypes.h | 2 +- msvc/71/libbulletdynamics.vcproj | 142 ++++---- msvc/8/libbulletdynamics.vcproj | 319 +++++++++++------- msvc/8/wksbullet.sln | 180 +--------- 8 files changed, 540 insertions(+), 388 deletions(-) create mode 100644 BulletDynamics/ConstraintSolver/Generic6DofConstraint.cpp create mode 100644 BulletDynamics/ConstraintSolver/Generic6DofConstraint.h diff --git a/BulletDynamics/ConstraintSolver/Generic6DofConstraint.cpp b/BulletDynamics/ConstraintSolver/Generic6DofConstraint.cpp new file mode 100644 index 000000000..c10a588ee --- /dev/null +++ b/BulletDynamics/ConstraintSolver/Generic6DofConstraint.cpp @@ -0,0 +1,175 @@ +/* +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 "Generic6DofConstraint.h" +#include "Dynamics/RigidBody.h" +#include "Dynamics/MassProps.h" +#include "SimdTransformUtil.h" + + +Generic6DofConstraint::Generic6DofConstraint() +{ +} + +Generic6DofConstraint::Generic6DofConstraint(RigidBody& rbA,RigidBody& rbB, const SimdVector3& pivotInA,const SimdVector3& pivotInB, + SimdVector3& axisInA,SimdVector3& axisInB) +:TypedConstraint(rbA,rbB),m_pivotInA(pivotInA),m_pivotInB(pivotInB), +m_axisInA(axisInA), +m_axisInB(axisInB) +{ + +} + + +Generic6DofConstraint::Generic6DofConstraint(RigidBody& rbA,const SimdVector3& pivotInA,SimdVector3& axisInA) +:TypedConstraint(rbA),m_pivotInA(pivotInA),m_pivotInB(rbA.getCenterOfMassTransform()(pivotInA)), +m_axisInA(axisInA), +//fixed axis in worldspace +m_axisInB(rbA.getCenterOfMassTransform().getBasis() * -axisInA) + +{ + +} + +void Generic6DofConstraint::BuildJacobian() +{ + SimdVector3 normal(0,0,0); + + //linear part + { + for (int i=0;i<3;i++) + { + normal[i] = 1; + new (&m_jac[i]) JacobianEntry( + m_rbA.getCenterOfMassTransform().getBasis().transpose(), + m_rbB.getCenterOfMassTransform().getBasis().transpose(), + m_rbA.getCenterOfMassTransform()*m_pivotInA - m_rbA.getCenterOfMassPosition(), + m_rbB.getCenterOfMassTransform()*m_pivotInB - m_rbB.getCenterOfMassPosition(), + normal, + m_rbA.getInvInertiaDiagLocal(), + m_rbA.getInvMass(), + m_rbB.getInvInertiaDiagLocal(), + m_rbB.getInvMass()); + normal[i] = 0; + } + } + + //calculate two perpendicular jointAxis, orthogonal to hingeAxis + //these two jointAxis require equal angular velocities for both bodies + + //this is ununsed for now, it's a todo + SimdVector3 axisWorldA = GetRigidBodyA().getCenterOfMassTransform().getBasis() * m_axisInA; + SimdVector3 jointAxis0; + SimdVector3 jointAxis1; + SimdPlaneSpace1(axisWorldA,jointAxis0,jointAxis1); + + new (&m_jacAng[0]) JacobianEntry(jointAxis0, + m_rbA.getCenterOfMassTransform().getBasis().transpose(), + m_rbB.getCenterOfMassTransform().getBasis().transpose(), + m_rbA.getInvInertiaDiagLocal(), + m_rbB.getInvInertiaDiagLocal()); + + new (&m_jacAng[1]) JacobianEntry(jointAxis1, + m_rbA.getCenterOfMassTransform().getBasis().transpose(), + m_rbB.getCenterOfMassTransform().getBasis().transpose(), + m_rbA.getInvInertiaDiagLocal(), + m_rbB.getInvInertiaDiagLocal()); + + +} + +void Generic6DofConstraint::SolveConstraint(SimdScalar timeStep) +{ + + SimdVector3 pivotAInW = m_rbA.getCenterOfMassTransform()*m_pivotInA; + SimdVector3 pivotBInW = m_rbB.getCenterOfMassTransform()*m_pivotInB; + + SimdVector3 normal(0,0,0); + SimdScalar tau = 0.3f; + SimdScalar damping = 1.f; + +//linear part + { + for (int i=0;i<3;i++) + { + normal[i] = 1; + SimdScalar jacDiagABInv = 1.f / m_jac[i].getDiagonal(); + + SimdVector3 rel_pos1 = pivotAInW - m_rbA.getCenterOfMassPosition(); + SimdVector3 rel_pos2 = pivotBInW - m_rbB.getCenterOfMassPosition(); + + SimdVector3 vel1 = m_rbA.getVelocityInLocalPoint(rel_pos1); + SimdVector3 vel2 = m_rbB.getVelocityInLocalPoint(rel_pos2); + SimdVector3 vel = vel1 - vel2; + SimdScalar rel_vel; + rel_vel = normal.dot(vel); + //positional error (zeroth order error) + SimdScalar depth = -(pivotAInW - pivotBInW).dot(normal); //this is the error projected on the normal + SimdScalar impulse = depth*tau/timeStep * jacDiagABInv - damping * rel_vel * jacDiagABInv * damping; + + SimdVector3 impulse_vector = normal * impulse; + m_rbA.applyImpulse(impulse_vector, pivotAInW - m_rbA.getCenterOfMassPosition()); + m_rbB.applyImpulse(-impulse_vector, pivotBInW - m_rbB.getCenterOfMassPosition()); + + normal[i] = 0; + } + } + + ///solve angular part + + // get axes in world space + SimdVector3 axisA = GetRigidBodyA().getCenterOfMassTransform().getBasis() * m_axisInA; + SimdVector3 axisB = GetRigidBodyB().getCenterOfMassTransform().getBasis() * m_axisInB; + + const SimdVector3& angVelA = GetRigidBodyA().getAngularVelocity(); + const SimdVector3& angVelB = GetRigidBodyB().getAngularVelocity(); + SimdVector3 angA = angVelA - axisA * axisA.dot(angVelA); + SimdVector3 angB = angVelB - axisB * axisB.dot(angVelB); + SimdVector3 velrel = angA-angB; + + //solve angular velocity correction + float relaxation = 1.f; + float len = velrel.length(); + if (len > 0.00001f) + { + SimdVector3 normal = velrel.normalized(); + float denom = GetRigidBodyA().ComputeAngularImpulseDenominator(normal) + + GetRigidBodyB().ComputeAngularImpulseDenominator(normal); + // scale for mass and relaxation + velrel *= (1.f/denom) * 0.9; + } + + //solve angular positional correction + SimdVector3 angularError = -axisA.cross(axisB) *(1.f/timeStep); + float len2 = angularError.length(); + if (len2>0.00001f) + { + SimdVector3 normal2 = angularError.normalized(); + float denom2 = GetRigidBodyA().ComputeAngularImpulseDenominator(normal2) + + GetRigidBodyB().ComputeAngularImpulseDenominator(normal2); + angularError *= (1.f/denom2) * relaxation; + } + + m_rbA.applyTorqueImpulse(-velrel+angularError); + m_rbB.applyTorqueImpulse(velrel-angularError); + +} + +void Generic6DofConstraint::UpdateRHS(SimdScalar timeStep) +{ + +} + diff --git a/BulletDynamics/ConstraintSolver/Generic6DofConstraint.h b/BulletDynamics/ConstraintSolver/Generic6DofConstraint.h new file mode 100644 index 000000000..660368571 --- /dev/null +++ b/BulletDynamics/ConstraintSolver/Generic6DofConstraint.h @@ -0,0 +1,68 @@ +/* +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. +*/ + +#ifndef GENERIC_6DOF_CONSTRAINT_H +#define GENERIC_6DOF_CONSTRAINT_H + +#include "SimdVector3.h" + +#include "ConstraintSolver/JacobianEntry.h" +#include "TypedConstraint.h" + +class RigidBody; + + + +/// Generic6DofConstraint between two rigidbodies each with a pivotpoint that descibes the axis location in local space +/// Generic6DofConstraint can leave any of the 6 degree of freedom 'free' or 'locked' +/// Work in progress (is still a Hinge actually) +class Generic6DofConstraint : public TypedConstraint +{ + JacobianEntry m_jac[3]; //3 orthogonal linear constraints + JacobianEntry m_jacAng[3]; //3 orthogonal angular constraints + + SimdVector3 m_pivotInA; + SimdVector3 m_pivotInB; + SimdVector3 m_axisInA; + SimdVector3 m_axisInB; + + +public: + + Generic6DofConstraint(RigidBody& rbA,RigidBody& rbB, const SimdVector3& pivotInA,const SimdVector3& pivotInB,SimdVector3& axisInA,SimdVector3& axisInB); + + Generic6DofConstraint(RigidBody& rbA,const SimdVector3& pivotInA,SimdVector3& axisInA); + + Generic6DofConstraint(); + + virtual void BuildJacobian(); + + virtual void SolveConstraint(SimdScalar timeStep); + + void UpdateRHS(SimdScalar timeStep); + + const RigidBody& GetRigidBodyA() const + { + return m_rbA; + } + const RigidBody& GetRigidBodyB() const + { + return m_rbB; + } + + +}; + +#endif //GENERIC_6DOF_CONSTRAINT_H diff --git a/Demos/ConstraintDemo/ConstraintDemo.cpp b/Demos/ConstraintDemo/ConstraintDemo.cpp index 9733627cd..cd2c2ae37 100644 --- a/Demos/ConstraintDemo/ConstraintDemo.cpp +++ b/Demos/ConstraintDemo/ConstraintDemo.cpp @@ -126,7 +126,7 @@ int main(int argc,char** argv) shapeProps.m_shape->SetMargin(0.05f); - bool isDyna = i>0; + bool isDyna = i>1; if (0)//i==1) { @@ -188,16 +188,17 @@ int main(int argc,char** argv) int constraintId; float pivotX=CUBE_HALF_EXTENTS, - pivotY=CUBE_HALF_EXTENTS, - pivotZ=CUBE_HALF_EXTENTS; - float axisX=0,axisY=1,axisZ=0; + pivotY=-CUBE_HALF_EXTENTS, + pivotZ=-CUBE_HALF_EXTENTS; + float axisX=0,axisY=0,axisZ=1; constraintId =physicsEnvironmentPtr->createConstraint( physObjects[1], //0, physObjects[2], - PHY_POINT2POINT_CONSTRAINT, + //PHY_POINT2POINT_CONSTRAINT, + PHY_GENERIC_6DOF_CONSTRAINT,//can leave any of the 6 degree of freedom 'free' or 'locked' //PHY_LINEHINGE_CONSTRAINT, pivotX,pivotY,pivotZ, axisX,axisY,axisZ diff --git a/Extras/PhysicsInterface/CcdPhysics/CcdPhysicsEnvironment.cpp b/Extras/PhysicsInterface/CcdPhysics/CcdPhysicsEnvironment.cpp index 4b4d3f15d..199cb56bc 100644 --- a/Extras/PhysicsInterface/CcdPhysics/CcdPhysicsEnvironment.cpp +++ b/Extras/PhysicsInterface/CcdPhysics/CcdPhysicsEnvironment.cpp @@ -77,6 +77,9 @@ RaycastVehicle::VehicleTuning gTuning; #include "ConstraintSolver/ConstraintSolver.h" #include "ConstraintSolver/Point2PointConstraint.h" #include "ConstraintSolver/HingeConstraint.h" +#include "ConstraintSolver/Generic6DofConstraint.h" + + //#include "BroadphaseCollision/QueryDispatcher.h" @@ -1184,9 +1187,37 @@ int CcdPhysicsEnvironment::createConstraint(class PHY_IPhysicsController* ctrl break; } + case PHY_GENERIC_6DOF_CONSTRAINT: + { + Generic6DofConstraint* genericConstraint = 0; + + if (rb1) + { + genericConstraint = new Generic6DofConstraint( + *rb0, + *rb1,pivotInA,pivotInB,axisInA,axisInB); + + + } else + { + genericConstraint = new Generic6DofConstraint(*rb0, + pivotInA,axisInA); + + } + + + m_constraints.push_back(genericConstraint); + genericConstraint->SetUserConstraintId(gConstraintUid++); + genericConstraint->SetUserConstraintType(type); + //64 bit systems can't cast pointer to int. could use size_t instead. + return genericConstraint->GetUserConstraintId(); + + break; + } case PHY_ANGULAR_CONSTRAINT: angularOnly = true; + case PHY_LINEHINGE_CONSTRAINT: { HingeConstraint* hinge = 0; diff --git a/Extras/PhysicsInterface/Common/PHY_DynamicTypes.h b/Extras/PhysicsInterface/Common/PHY_DynamicTypes.h index 79cd57756..395237718 100644 --- a/Extras/PhysicsInterface/Common/PHY_DynamicTypes.h +++ b/Extras/PhysicsInterface/Common/PHY_DynamicTypes.h @@ -82,7 +82,7 @@ typedef enum PHY_ConstraintType { PHY_LINEHINGE_CONSTRAINT=2, PHY_ANGULAR_CONSTRAINT = 3,//hinge without ball socket PHY_VEHICLE_CONSTRAINT=11,//complex 'constraint' that turns a rigidbody into a vehicle - + PHY_GENERIC_6DOF_CONSTRAINT=12,//can leave any of the 6 degree of freedom 'free' or 'locked' } PHY_ConstraintType; diff --git a/msvc/71/libbulletdynamics.vcproj b/msvc/71/libbulletdynamics.vcproj index e6f650fb6..0cebc39e5 100644 --- a/msvc/71/libbulletdynamics.vcproj +++ b/msvc/71/libbulletdynamics.vcproj @@ -1,4 +1,4 @@ - + - + Name="VCPostBuildEventTool"/> + Culture="1033" + AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"/> + Name="VCXMLDataGeneratorTool"/> + + - + Name="VCPostBuildEventTool"/> + Culture="1033" + AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"/> + Name="VCXMLDataGeneratorTool"/> + + + + + + + + @@ -171,6 +159,9 @@ + + @@ -183,25 +174,22 @@ - - - - - - + + + + @@ -211,12 +199,18 @@ + + + + @@ -229,19 +223,13 @@ - - - - - - - - + + + + diff --git a/msvc/8/libbulletdynamics.vcproj b/msvc/8/libbulletdynamics.vcproj index ebeaafa63..74b9c390a 100644 --- a/msvc/8/libbulletdynamics.vcproj +++ b/msvc/8/libbulletdynamics.vcproj @@ -1,15 +1,18 @@ - + + RootNamespace="libbulletdynamics" + > + Name="Win32" + /> + + + ATLMinimizesCRunTimeLibraryUsage="false" + > + + + + + + SuppressStartupBanner="true" + Detect64BitPortabilityProblems="true" + DebugInformationFormat="3" + CompileAs="0" + /> - - - - - - + Name="VCManagedResourceCompilerTool" + /> + /> + Name="VCPreLinkEventTool" + /> + Name="VCLibrarianTool" + OutputFile="..\..\out\release8\libs\libbulletdynamics.lib" + SuppressStartupBanner="true" + /> + + + + + + ATLMinimizesCRunTimeLibraryUsage="false" + > + + + + + + SuppressStartupBanner="true" + Detect64BitPortabilityProblems="true" + DebugInformationFormat="4" + CompileAs="0" + /> - - - - - - + Name="VCManagedResourceCompilerTool" + /> + /> + Name="VCPreLinkEventTool" + /> + Name="VCLibrarianTool" + OutputFile="..\..\out\debug8\libs\libbulletdynamics_d.lib" + SuppressStartupBanner="true" + /> + + + + + + + + > + RelativePath="..\..\BulletDynamics\Dynamics\BU_Joint.cpp" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactConstraint.cpp" + > + RelativePath="..\..\BulletDynamics\Dynamics\ContactJoint.cpp" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\Generic6DofConstraint.cpp" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\HingeConstraint.cpp" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\OdeConstraintSolver.cpp" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\Point2PointConstraint.cpp" + > + RelativePath="..\..\BulletDynamics\Dynamics\RigidBody.cpp" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\SimpleConstraintSolver.cpp" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\Solve2LinearConstraint.cpp" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\SorLcp.cpp" + > + + + > + RelativePath="..\..\BulletDynamics\Dynamics\BU_Joint.h" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\ConstraintSolver.h" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactConstraint.h" + > + RelativePath="..\..\BulletDynamics\Dynamics\ContactJoint.h" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactSolverInfo.h" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\Generic6DofConstraint.h" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\HingeConstraint.h" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\JacobianEntry.h" + > + RelativePath="..\..\BulletDynamics\Dynamics\MassProps.h" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\OdeConstraintSolver.h" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\Point2PointConstraint.h" + > + RelativePath="..\..\BulletDynamics\Dynamics\RigidBody.h" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\SimpleConstraintSolver.h" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\Solve2LinearConstraint.h" + > + RelativePath="..\..\BulletDynamics\ConstraintSolver\SorLcp.h" + > + + diff --git a/msvc/8/wksbullet.sln b/msvc/8/wksbullet.sln index 862c16b09..2a2a8646b 100644 --- a/msvc/8/wksbullet.sln +++ b/msvc/8/wksbullet.sln @@ -21,10 +21,6 @@ Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appCcdPhysicsDemo", "appCcd 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} - {46DC0A36-30B8-4004-94AD-96C607F3983A} = {46DC0A36-30B8-4004-94AD-96C607F3983A} - {63985384-2FBF-4796-96F1-F0AE163BAFC9} = {63985384-2FBF-4796-96F1-F0AE163BAFC9} - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C} = {EEAD895E-87CF-4A0A-AAC6-951D96977E2C} {D7F466F4-2AEA-4648-BE09-024C887BC157} = {D7F466F4-2AEA-4648-BE09-024C887BC157} {FF956BB3-F377-43A8-AB31-633299BDF6C6} = {FF956BB3-F377-43A8-AB31-633299BDF6C6} {3D872CA6-782B-46C9-A336-1B18C0A4FBD5} = {3D872CA6-782B-46C9-A336-1B18C0A4FBD5} @@ -35,8 +31,7 @@ Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appColladaDemo", "appCollad {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97} {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} {85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822} - {B70CBA1A-414C-4872-8DAF-31934BCAB568} = {B70CBA1A-414C-4872-8DAF-31934BCAB568} - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E} = {4A974C64-D51F-4D0F-85B8-0C876EF29F2E} + {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC} = {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC} EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appCollisionDemo", "appCollisionDemo.vcproj", "{E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}" @@ -209,6 +204,9 @@ 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}" + ProjectSection(ProjectDependencies) = postProject + {FF956BB3-F377-43A8-AB31-633299BDF6C6} = {FF956BB3-F377-43A8-AB31-633299BDF6C6} + EndProjectSection EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "FMath_vc8", "..\..\Extras\FCollada\FMath\FMath_vc8.vcproj", "{38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}" EndProject @@ -216,16 +214,6 @@ Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "FUtils_vc8", "..\..\Extras\ EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "LibXML_vc8", "..\..\Extras\FCollada\LibXML\LibXML_vc8.vcproj", "{D7F466F4-2AEA-4648-BE09-024C887BC157}" EndProject -Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "dom1", "..\..\Extras\COLLADA_DOM\src\1.4\dom\dom1.4_vc8.vcproj", "{EEAD895E-87CF-4A0A-AAC6-951D96977E2C}" -EndProject -Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "dae_vc8", "..\..\Extras\COLLADA_DOM\src\dae\dae_vc8.vcproj", "{B70CBA1A-414C-4872-8DAF-31934BCAB568}" -EndProject -Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "STLDatabase_vc8", "..\..\Extras\COLLADA_DOM\src\modules\STLDatabase\STLDatabase_vc8.vcproj", "{63985384-2FBF-4796-96F1-F0AE163BAFC9}" -EndProject -Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "LIBXMLPlugin_vc8", "..\..\Extras\COLLADA_DOM\src\modules\LIBXMLPlugin\LIBXMLPlugin_vc8.vcproj", "{4A974C64-D51F-4D0F-85B8-0C876EF29F2E}" -EndProject -Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "stdErrPlugin_vc8", "..\..\Extras\COLLADA_DOM\src\modules\stdErrPlugin\stdErrPlugin_vc8.vcproj", "{46DC0A36-30B8-4004-94AD-96C607F3983A}" -EndProject Global GlobalSection(SolutionConfigurationPlatforms) = preSolution Debug DLL|Win32 = Debug DLL|Win32 @@ -1142,166 +1130,6 @@ Global {D7F466F4-2AEA-4648-BE09-024C887BC157}.Release(1.4)|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 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug DLL|Win32.ActiveCfg = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug DLL|Win32.Build.0 = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug MTD|Win32.ActiveCfg = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug MTD|Win32.Build.0 = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug Unicode DLL|Win32.ActiveCfg = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug Unicode DLL|Win32.Build.0 = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug Unicode MTD|Win32.ActiveCfg = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug Unicode MTD|Win32.Build.0 = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug Unicode|Win32.ActiveCfg = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug Unicode|Win32.Build.0 = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug(1.3)|Win32.ActiveCfg = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug(1.3)|Win32.Build.0 = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug(1.4)|Win32.ActiveCfg = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug(1.4)|Win32.Build.0 = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug|Win32.ActiveCfg = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Debug|Win32.Build.0 = Debug(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release DLL|Win32.ActiveCfg = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release DLL|Win32.Build.0 = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release MTD|Win32.ActiveCfg = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release MTD|Win32.Build.0 = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release Unicode DLL|Win32.ActiveCfg = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release Unicode DLL|Win32.Build.0 = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release Unicode MTD|Win32.ActiveCfg = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release Unicode MTD|Win32.Build.0 = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release Unicode|Win32.ActiveCfg = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release Unicode|Win32.Build.0 = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release(1.3)|Win32.ActiveCfg = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release(1.3)|Win32.Build.0 = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release(1.4)|Win32.ActiveCfg = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release(1.4)|Win32.Build.0 = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release|Win32.ActiveCfg = Release(1.4)|Win32 - {EEAD895E-87CF-4A0A-AAC6-951D96977E2C}.Release|Win32.Build.0 = Release(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug DLL|Win32.ActiveCfg = Debug(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug DLL|Win32.Build.0 = Debug(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug MTD|Win32.ActiveCfg = Debug(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug MTD|Win32.Build.0 = Debug(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug Unicode DLL|Win32.ActiveCfg = Debug(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug Unicode DLL|Win32.Build.0 = Debug(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug Unicode MTD|Win32.ActiveCfg = Debug(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug Unicode MTD|Win32.Build.0 = Debug(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug Unicode|Win32.ActiveCfg = Debug(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug Unicode|Win32.Build.0 = Debug(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug(1.3)|Win32.ActiveCfg = Debug(1.3)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug(1.3)|Win32.Build.0 = Debug(1.3)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug(1.4)|Win32.ActiveCfg = Debug(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug(1.4)|Win32.Build.0 = Debug(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug|Win32.ActiveCfg = Debug(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Debug|Win32.Build.0 = Debug(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release DLL|Win32.ActiveCfg = Release(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release DLL|Win32.Build.0 = Release(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release MTD|Win32.ActiveCfg = Release(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release MTD|Win32.Build.0 = Release(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release Unicode DLL|Win32.ActiveCfg = Release(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release Unicode DLL|Win32.Build.0 = Release(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release Unicode MTD|Win32.ActiveCfg = Release(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release Unicode MTD|Win32.Build.0 = Release(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release Unicode|Win32.ActiveCfg = Release(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release Unicode|Win32.Build.0 = Release(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release(1.3)|Win32.ActiveCfg = Release(1.3)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release(1.3)|Win32.Build.0 = Release(1.3)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release(1.4)|Win32.ActiveCfg = Release(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release(1.4)|Win32.Build.0 = Release(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release|Win32.ActiveCfg = Release(1.4)|Win32 - {B70CBA1A-414C-4872-8DAF-31934BCAB568}.Release|Win32.Build.0 = Release(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug DLL|Win32.ActiveCfg = Debug(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug DLL|Win32.Build.0 = Debug(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug MTD|Win32.ActiveCfg = Debug(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug MTD|Win32.Build.0 = Debug(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug Unicode DLL|Win32.ActiveCfg = Debug(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug Unicode DLL|Win32.Build.0 = Debug(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug Unicode MTD|Win32.ActiveCfg = Debug(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug Unicode MTD|Win32.Build.0 = Debug(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug Unicode|Win32.ActiveCfg = Debug(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug Unicode|Win32.Build.0 = Debug(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug(1.3)|Win32.ActiveCfg = Debug(1.3)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug(1.3)|Win32.Build.0 = Debug(1.3)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug(1.4)|Win32.ActiveCfg = Debug(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug(1.4)|Win32.Build.0 = Debug(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug|Win32.ActiveCfg = Debug(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Debug|Win32.Build.0 = Debug(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release DLL|Win32.ActiveCfg = Release(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release DLL|Win32.Build.0 = Release(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release MTD|Win32.ActiveCfg = Release(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release MTD|Win32.Build.0 = Release(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release Unicode DLL|Win32.ActiveCfg = Release(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release Unicode DLL|Win32.Build.0 = Release(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release Unicode MTD|Win32.ActiveCfg = Release(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release Unicode MTD|Win32.Build.0 = Release(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release Unicode|Win32.ActiveCfg = Release(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release Unicode|Win32.Build.0 = Release(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release(1.3)|Win32.ActiveCfg = Release(1.3)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release(1.3)|Win32.Build.0 = Release(1.3)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release(1.4)|Win32.ActiveCfg = Release(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release(1.4)|Win32.Build.0 = Release(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release|Win32.ActiveCfg = Release(1.4)|Win32 - {63985384-2FBF-4796-96F1-F0AE163BAFC9}.Release|Win32.Build.0 = Release(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug DLL|Win32.ActiveCfg = Debug(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug DLL|Win32.Build.0 = Debug(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug MTD|Win32.ActiveCfg = Debug(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug MTD|Win32.Build.0 = Debug(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug Unicode DLL|Win32.ActiveCfg = Debug(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug Unicode DLL|Win32.Build.0 = Debug(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug Unicode MTD|Win32.ActiveCfg = Debug(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug Unicode MTD|Win32.Build.0 = Debug(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug Unicode|Win32.ActiveCfg = Debug(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug Unicode|Win32.Build.0 = Debug(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug(1.3)|Win32.ActiveCfg = Debug(1.3)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug(1.3)|Win32.Build.0 = Debug(1.3)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug(1.4)|Win32.ActiveCfg = Debug(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug(1.4)|Win32.Build.0 = Debug(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug|Win32.ActiveCfg = Debug(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Debug|Win32.Build.0 = Debug(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release DLL|Win32.ActiveCfg = Release(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release DLL|Win32.Build.0 = Release(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release MTD|Win32.ActiveCfg = Release(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release MTD|Win32.Build.0 = Release(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release Unicode DLL|Win32.ActiveCfg = Release(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release Unicode DLL|Win32.Build.0 = Release(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release Unicode MTD|Win32.ActiveCfg = Release(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release Unicode MTD|Win32.Build.0 = Release(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release Unicode|Win32.ActiveCfg = Release(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release Unicode|Win32.Build.0 = Release(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release(1.3)|Win32.ActiveCfg = Release(1.3)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release(1.3)|Win32.Build.0 = Release(1.3)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release(1.4)|Win32.ActiveCfg = Release(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release(1.4)|Win32.Build.0 = Release(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release|Win32.ActiveCfg = Release(1.4)|Win32 - {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}.Release|Win32.Build.0 = Release(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug DLL|Win32.ActiveCfg = Debug(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug DLL|Win32.Build.0 = Debug(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug MTD|Win32.ActiveCfg = Debug(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug MTD|Win32.Build.0 = Debug(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug Unicode DLL|Win32.ActiveCfg = Debug(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug Unicode DLL|Win32.Build.0 = Debug(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug Unicode MTD|Win32.ActiveCfg = Debug(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug Unicode MTD|Win32.Build.0 = Debug(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug Unicode|Win32.ActiveCfg = Debug(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug Unicode|Win32.Build.0 = Debug(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug(1.3)|Win32.ActiveCfg = Debug(1.3)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug(1.3)|Win32.Build.0 = Debug(1.3)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug(1.4)|Win32.ActiveCfg = Debug(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug(1.4)|Win32.Build.0 = Debug(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug|Win32.ActiveCfg = Debug(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Debug|Win32.Build.0 = Debug(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release DLL|Win32.ActiveCfg = Release(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release DLL|Win32.Build.0 = Release(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release MTD|Win32.ActiveCfg = Release(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release MTD|Win32.Build.0 = Release(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release Unicode DLL|Win32.ActiveCfg = Release(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release Unicode DLL|Win32.Build.0 = Release(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release Unicode MTD|Win32.ActiveCfg = Release(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release Unicode MTD|Win32.Build.0 = Release(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release Unicode|Win32.ActiveCfg = Release(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release Unicode|Win32.Build.0 = Release(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release(1.3)|Win32.ActiveCfg = Release(1.3)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release(1.3)|Win32.Build.0 = Release(1.3)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release(1.4)|Win32.ActiveCfg = Release(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release(1.4)|Win32.Build.0 = Release(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release|Win32.ActiveCfg = Release(1.4)|Win32 - {46DC0A36-30B8-4004-94AD-96C607F3983A}.Release|Win32.Build.0 = Release(1.4)|Win32 EndGlobalSection GlobalSection(SolutionProperties) = preSolution HideSolutionNode = FALSE