Added Generic 6 DOF Constraint skeleton
This commit is contained in:
175
BulletDynamics/ConstraintSolver/Generic6DofConstraint.cpp
Normal file
175
BulletDynamics/ConstraintSolver/Generic6DofConstraint.cpp
Normal file
@@ -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)
|
||||||
|
{
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
68
BulletDynamics/ConstraintSolver/Generic6DofConstraint.h
Normal file
68
BulletDynamics/ConstraintSolver/Generic6DofConstraint.h
Normal file
@@ -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
|
||||||
@@ -126,7 +126,7 @@ int main(int argc,char** argv)
|
|||||||
shapeProps.m_shape->SetMargin(0.05f);
|
shapeProps.m_shape->SetMargin(0.05f);
|
||||||
|
|
||||||
|
|
||||||
bool isDyna = i>0;
|
bool isDyna = i>1;
|
||||||
|
|
||||||
if (0)//i==1)
|
if (0)//i==1)
|
||||||
{
|
{
|
||||||
@@ -188,16 +188,17 @@ int main(int argc,char** argv)
|
|||||||
int constraintId;
|
int constraintId;
|
||||||
|
|
||||||
float pivotX=CUBE_HALF_EXTENTS,
|
float pivotX=CUBE_HALF_EXTENTS,
|
||||||
pivotY=CUBE_HALF_EXTENTS,
|
pivotY=-CUBE_HALF_EXTENTS,
|
||||||
pivotZ=CUBE_HALF_EXTENTS;
|
pivotZ=-CUBE_HALF_EXTENTS;
|
||||||
float axisX=0,axisY=1,axisZ=0;
|
float axisX=0,axisY=0,axisZ=1;
|
||||||
|
|
||||||
|
|
||||||
constraintId =physicsEnvironmentPtr->createConstraint(
|
constraintId =physicsEnvironmentPtr->createConstraint(
|
||||||
physObjects[1],
|
physObjects[1],
|
||||||
//0,
|
//0,
|
||||||
physObjects[2],
|
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,
|
//PHY_LINEHINGE_CONSTRAINT,
|
||||||
pivotX,pivotY,pivotZ,
|
pivotX,pivotY,pivotZ,
|
||||||
axisX,axisY,axisZ
|
axisX,axisY,axisZ
|
||||||
|
|||||||
@@ -77,6 +77,9 @@ RaycastVehicle::VehicleTuning gTuning;
|
|||||||
#include "ConstraintSolver/ConstraintSolver.h"
|
#include "ConstraintSolver/ConstraintSolver.h"
|
||||||
#include "ConstraintSolver/Point2PointConstraint.h"
|
#include "ConstraintSolver/Point2PointConstraint.h"
|
||||||
#include "ConstraintSolver/HingeConstraint.h"
|
#include "ConstraintSolver/HingeConstraint.h"
|
||||||
|
#include "ConstraintSolver/Generic6DofConstraint.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//#include "BroadphaseCollision/QueryDispatcher.h"
|
//#include "BroadphaseCollision/QueryDispatcher.h"
|
||||||
@@ -1184,9 +1187,37 @@ int CcdPhysicsEnvironment::createConstraint(class PHY_IPhysicsController* ctrl
|
|||||||
break;
|
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:
|
case PHY_ANGULAR_CONSTRAINT:
|
||||||
angularOnly = true;
|
angularOnly = true;
|
||||||
|
|
||||||
|
|
||||||
case PHY_LINEHINGE_CONSTRAINT:
|
case PHY_LINEHINGE_CONSTRAINT:
|
||||||
{
|
{
|
||||||
HingeConstraint* hinge = 0;
|
HingeConstraint* hinge = 0;
|
||||||
|
|||||||
@@ -82,7 +82,7 @@ typedef enum PHY_ConstraintType {
|
|||||||
PHY_LINEHINGE_CONSTRAINT=2,
|
PHY_LINEHINGE_CONSTRAINT=2,
|
||||||
PHY_ANGULAR_CONSTRAINT = 3,//hinge without ball socket
|
PHY_ANGULAR_CONSTRAINT = 3,//hinge without ball socket
|
||||||
PHY_VEHICLE_CONSTRAINT=11,//complex 'constraint' that turns a rigidbody into a vehicle
|
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;
|
} PHY_ConstraintType;
|
||||||
|
|
||||||
|
|||||||
@@ -1,4 +1,4 @@
|
|||||||
<?xml version="1.0" encoding = "Windows-1252"?>
|
<?xml version="1.0" encoding="Windows-1252"?>
|
||||||
<VisualStudioProject
|
<VisualStudioProject
|
||||||
ProjectType="Visual C++"
|
ProjectType="Visual C++"
|
||||||
Version="7.10"
|
Version="7.10"
|
||||||
@@ -20,17 +20,17 @@
|
|||||||
ATLMinimizesCRunTimeLibraryUsage="FALSE">
|
ATLMinimizesCRunTimeLibraryUsage="FALSE">
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCCLCompilerTool"
|
Name="VCCLCompilerTool"
|
||||||
Optimization="2"
|
|
||||||
StringPooling="TRUE"
|
|
||||||
EnableFunctionLevelLinking="TRUE"
|
|
||||||
RuntimeLibrary="2"
|
|
||||||
DebugInformationFormat="3"
|
|
||||||
BufferSecurityCheck="FALSE"
|
|
||||||
PreprocessorDefinitions="NDEBUG;_LIB;_WINDOWS;WIN32"
|
|
||||||
OptimizeForProcessor="1"
|
|
||||||
ExceptionHandling="0"
|
|
||||||
AdditionalOptions=" "
|
AdditionalOptions=" "
|
||||||
|
Optimization="2"
|
||||||
|
OptimizeForProcessor="1"
|
||||||
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"
|
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"
|
||||||
|
PreprocessorDefinitions="NDEBUG;_LIB;_WINDOWS;WIN32"
|
||||||
|
StringPooling="TRUE"
|
||||||
|
ExceptionHandling="FALSE"
|
||||||
|
RuntimeLibrary="2"
|
||||||
|
BufferSecurityCheck="FALSE"
|
||||||
|
EnableFunctionLevelLinking="TRUE"
|
||||||
|
TreatWChar_tAsBuiltInType="FALSE"
|
||||||
PrecompiledHeaderFile="..\..\out\release71\build\libbulletdynamics\libbulletdynamics.pch"
|
PrecompiledHeaderFile="..\..\out\release71\build\libbulletdynamics\libbulletdynamics.pch"
|
||||||
AssemblerListingLocation="..\..\out\release71\build\libbulletdynamics\"
|
AssemblerListingLocation="..\..\out\release71\build\libbulletdynamics\"
|
||||||
ObjectFile="..\..\out\release71\build\libbulletdynamics\"
|
ObjectFile="..\..\out\release71\build\libbulletdynamics\"
|
||||||
@@ -38,24 +38,10 @@
|
|||||||
WarningLevel="3"
|
WarningLevel="3"
|
||||||
SuppressStartupBanner="TRUE"
|
SuppressStartupBanner="TRUE"
|
||||||
Detect64BitPortabilityProblems="TRUE"
|
Detect64BitPortabilityProblems="TRUE"
|
||||||
TreatWChar_tAsBuiltInType="false"
|
DebugInformationFormat="3"
|
||||||
CompileAs="0"/>
|
CompileAs="0"/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCCustomBuildTool"/>
|
Name="VCCustomBuildTool"/>
|
||||||
<Tool
|
|
||||||
Name="VCLinkerTool"
|
|
||||||
LinkIncremental="1"
|
|
||||||
OptimizeReferences="2"
|
|
||||||
EnableCOMDATFolding="2"
|
|
||||||
GenerateDebugInformation="TRUE"
|
|
||||||
IgnoreDefaultLibraryNames="LIBC,LIBCD,LIBCMT,LIBCMTD"
|
|
||||||
AdditionalOptions=" "
|
|
||||||
AdditionalDependencies=""
|
|
||||||
IgnoreImportLibrary="TRUE"
|
|
||||||
SuppressStartupBanner="TRUE"
|
|
||||||
AdditionalLibraryDirectories=""
|
|
||||||
ProgramDatabaseFile="..\..\out\release71\build\libbulletdynamics\bulletdynamics.pdb"
|
|
||||||
TargetMachine="1"/>
|
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCLibrarianTool"
|
Name="VCLibrarianTool"
|
||||||
OutputFile="..\..\out\release71\libs\libbulletdynamics.lib"
|
OutputFile="..\..\out\release71\libs\libbulletdynamics.lib"
|
||||||
@@ -68,8 +54,7 @@
|
|||||||
TargetEnvironment="1"
|
TargetEnvironment="1"
|
||||||
TypeLibraryName="..\..\out\release71\build\libbulletdynamics\libbulletdynamics.tlb"/>
|
TypeLibraryName="..\..\out\release71\build\libbulletdynamics\libbulletdynamics.tlb"/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCPostBuildEventTool"
|
Name="VCPostBuildEventTool"/>
|
||||||
/>
|
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCPreBuildEventTool"/>
|
Name="VCPreBuildEventTool"/>
|
||||||
<Tool
|
<Tool
|
||||||
@@ -77,12 +62,16 @@
|
|||||||
<Tool
|
<Tool
|
||||||
Name="VCResourceCompilerTool"
|
Name="VCResourceCompilerTool"
|
||||||
PreprocessorDefinitions="NDEBUG;_LIB;_WINDOWS;PROJECTGEN_VERSION=71"
|
PreprocessorDefinitions="NDEBUG;_LIB;_WINDOWS;PROJECTGEN_VERSION=71"
|
||||||
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"
|
Culture="1033"
|
||||||
Culture="1033"/>
|
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCWebServiceProxyGeneratorTool"/>
|
Name="VCWebServiceProxyGeneratorTool"/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCWebDeploymentTool"/>
|
Name="VCXMLDataGeneratorTool"/>
|
||||||
|
<Tool
|
||||||
|
Name="VCManagedWrapperGeneratorTool"/>
|
||||||
|
<Tool
|
||||||
|
Name="VCAuxiliaryManagedWrapperGeneratorTool"/>
|
||||||
</Configuration>
|
</Configuration>
|
||||||
<Configuration
|
<Configuration
|
||||||
Name="Debug|Win32"
|
Name="Debug|Win32"
|
||||||
@@ -93,16 +82,16 @@
|
|||||||
ATLMinimizesCRunTimeLibraryUsage="FALSE">
|
ATLMinimizesCRunTimeLibraryUsage="FALSE">
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCCLCompilerTool"
|
Name="VCCLCompilerTool"
|
||||||
Optimization="0"
|
|
||||||
MinimalRebuild="TRUE"
|
|
||||||
DebugInformationFormat="4"
|
|
||||||
RuntimeTypeInfo="TRUE"
|
|
||||||
RuntimeLibrary="3"
|
|
||||||
PreprocessorDefinitions="_DEBUG;_LIB;_WINDOWS;WIN32"
|
|
||||||
OptimizeForProcessor="1"
|
|
||||||
ExceptionHandling="0"
|
|
||||||
AdditionalOptions=" "
|
AdditionalOptions=" "
|
||||||
|
Optimization="0"
|
||||||
|
OptimizeForProcessor="1"
|
||||||
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"
|
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"
|
||||||
|
PreprocessorDefinitions="_DEBUG;_LIB;_WINDOWS;WIN32"
|
||||||
|
MinimalRebuild="TRUE"
|
||||||
|
ExceptionHandling="FALSE"
|
||||||
|
RuntimeLibrary="3"
|
||||||
|
TreatWChar_tAsBuiltInType="FALSE"
|
||||||
|
RuntimeTypeInfo="TRUE"
|
||||||
PrecompiledHeaderFile="..\..\out\debug71\build\libbulletdynamics\libbulletdynamics.pch"
|
PrecompiledHeaderFile="..\..\out\debug71\build\libbulletdynamics\libbulletdynamics.pch"
|
||||||
AssemblerListingLocation="..\..\out\debug71\build\libbulletdynamics\"
|
AssemblerListingLocation="..\..\out\debug71\build\libbulletdynamics\"
|
||||||
ObjectFile="..\..\out\debug71\build\libbulletdynamics\"
|
ObjectFile="..\..\out\debug71\build\libbulletdynamics\"
|
||||||
@@ -110,22 +99,10 @@
|
|||||||
WarningLevel="3"
|
WarningLevel="3"
|
||||||
SuppressStartupBanner="TRUE"
|
SuppressStartupBanner="TRUE"
|
||||||
Detect64BitPortabilityProblems="TRUE"
|
Detect64BitPortabilityProblems="TRUE"
|
||||||
TreatWChar_tAsBuiltInType="false"
|
DebugInformationFormat="4"
|
||||||
CompileAs="0"/>
|
CompileAs="0"/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCCustomBuildTool"/>
|
Name="VCCustomBuildTool"/>
|
||||||
<Tool
|
|
||||||
Name="VCLinkerTool"
|
|
||||||
LinkIncremental="2"
|
|
||||||
GenerateDebugInformation="TRUE"
|
|
||||||
IgnoreDefaultLibraryNames="LIBC,LIBCD,LIBCMT,LIBCMTD,MSVCRT"
|
|
||||||
AdditionalOptions=" "
|
|
||||||
AdditionalDependencies=""
|
|
||||||
IgnoreImportLibrary="TRUE"
|
|
||||||
SuppressStartupBanner="TRUE"
|
|
||||||
AdditionalLibraryDirectories=""
|
|
||||||
ProgramDatabaseFile="..\..\out\debug71\build\libbulletdynamics\bulletdynamics.pdb"
|
|
||||||
TargetMachine="1"/>
|
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCLibrarianTool"
|
Name="VCLibrarianTool"
|
||||||
OutputFile="..\..\out\debug71\libs\libbulletdynamics_d.lib"
|
OutputFile="..\..\out\debug71\libs\libbulletdynamics_d.lib"
|
||||||
@@ -138,8 +115,7 @@
|
|||||||
TargetEnvironment="1"
|
TargetEnvironment="1"
|
||||||
TypeLibraryName="..\..\out\debug71\build\libbulletdynamics\libbulletdynamics.tlb"/>
|
TypeLibraryName="..\..\out\debug71\build\libbulletdynamics\libbulletdynamics.tlb"/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCPostBuildEventTool"
|
Name="VCPostBuildEventTool"/>
|
||||||
/>
|
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCPreBuildEventTool"/>
|
Name="VCPreBuildEventTool"/>
|
||||||
<Tool
|
<Tool
|
||||||
@@ -147,21 +123,33 @@
|
|||||||
<Tool
|
<Tool
|
||||||
Name="VCResourceCompilerTool"
|
Name="VCResourceCompilerTool"
|
||||||
PreprocessorDefinitions="_DEBUG;_LIB;_WINDOWS;PROJECTGEN_VERSION=71"
|
PreprocessorDefinitions="_DEBUG;_LIB;_WINDOWS;PROJECTGEN_VERSION=71"
|
||||||
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"
|
Culture="1033"
|
||||||
Culture="1033"/>
|
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCWebServiceProxyGeneratorTool"/>
|
Name="VCWebServiceProxyGeneratorTool"/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCWebDeploymentTool"/>
|
Name="VCXMLDataGeneratorTool"/>
|
||||||
|
<Tool
|
||||||
|
Name="VCManagedWrapperGeneratorTool"/>
|
||||||
|
<Tool
|
||||||
|
Name="VCAuxiliaryManagedWrapperGeneratorTool"/>
|
||||||
</Configuration>
|
</Configuration>
|
||||||
</Configurations>
|
</Configurations>
|
||||||
|
<References>
|
||||||
|
</References>
|
||||||
<Files>
|
<Files>
|
||||||
<Filter
|
<Filter
|
||||||
Name="Source Files"
|
Name="Source Files"
|
||||||
Filter="">
|
Filter="">
|
||||||
|
<File
|
||||||
|
RelativePath="..\..\BulletDynamics\Dynamics\BU_Joint.cpp">
|
||||||
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactConstraint.cpp">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactConstraint.cpp">
|
||||||
</File>
|
</File>
|
||||||
|
<File
|
||||||
|
RelativePath="..\..\BulletDynamics\Dynamics\ContactJoint.cpp">
|
||||||
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\HingeConstraint.cpp">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\HingeConstraint.cpp">
|
||||||
</File>
|
</File>
|
||||||
@@ -171,6 +159,9 @@
|
|||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\Point2PointConstraint.cpp">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\Point2PointConstraint.cpp">
|
||||||
</File>
|
</File>
|
||||||
|
<File
|
||||||
|
RelativePath="..\..\BulletDynamics\Dynamics\RigidBody.cpp">
|
||||||
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\SimpleConstraintSolver.cpp">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\SimpleConstraintSolver.cpp">
|
||||||
</File>
|
</File>
|
||||||
@@ -183,25 +174,22 @@
|
|||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\TypedConstraint.cpp">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\TypedConstraint.cpp">
|
||||||
</File>
|
</File>
|
||||||
<File
|
|
||||||
RelativePath="..\..\BulletDynamics\Dynamics\BU_Joint.cpp">
|
|
||||||
</File>
|
|
||||||
<File
|
|
||||||
RelativePath="..\..\BulletDynamics\Dynamics\ContactJoint.cpp">
|
|
||||||
</File>
|
|
||||||
<File
|
|
||||||
RelativePath="..\..\BulletDynamics\Dynamics\RigidBody.cpp">
|
|
||||||
</File>
|
|
||||||
</Filter>
|
</Filter>
|
||||||
<Filter
|
<Filter
|
||||||
Name="Header Files"
|
Name="Header Files"
|
||||||
Filter="">
|
Filter="">
|
||||||
|
<File
|
||||||
|
RelativePath="..\..\BulletDynamics\Dynamics\BU_Joint.h">
|
||||||
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\ConstraintSolver.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\ConstraintSolver.h">
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactConstraint.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactConstraint.h">
|
||||||
</File>
|
</File>
|
||||||
|
<File
|
||||||
|
RelativePath="..\..\BulletDynamics\Dynamics\ContactJoint.h">
|
||||||
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactSolverInfo.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactSolverInfo.h">
|
||||||
</File>
|
</File>
|
||||||
@@ -211,12 +199,18 @@
|
|||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\JacobianEntry.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\JacobianEntry.h">
|
||||||
</File>
|
</File>
|
||||||
|
<File
|
||||||
|
RelativePath="..\..\BulletDynamics\Dynamics\MassProps.h">
|
||||||
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\OdeConstraintSolver.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\OdeConstraintSolver.h">
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\Point2PointConstraint.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\Point2PointConstraint.h">
|
||||||
</File>
|
</File>
|
||||||
|
<File
|
||||||
|
RelativePath="..\..\BulletDynamics\Dynamics\RigidBody.h">
|
||||||
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\SimpleConstraintSolver.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\SimpleConstraintSolver.h">
|
||||||
</File>
|
</File>
|
||||||
@@ -229,19 +223,13 @@
|
|||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\TypedConstraint.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\TypedConstraint.h">
|
||||||
</File>
|
</File>
|
||||||
<File
|
|
||||||
RelativePath="..\..\BulletDynamics\Dynamics\BU_Joint.h">
|
|
||||||
</File>
|
|
||||||
<File
|
|
||||||
RelativePath="..\..\BulletDynamics\Dynamics\ContactJoint.h">
|
|
||||||
</File>
|
|
||||||
<File
|
|
||||||
RelativePath="..\..\BulletDynamics\Dynamics\MassProps.h">
|
|
||||||
</File>
|
|
||||||
<File
|
|
||||||
RelativePath="..\..\BulletDynamics\Dynamics\RigidBody.h">
|
|
||||||
</File>
|
|
||||||
</Filter>
|
</Filter>
|
||||||
|
<File
|
||||||
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\Generic6DofConstraint.cpp">
|
||||||
|
</File>
|
||||||
|
<File
|
||||||
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\Generic6DofConstraint.h">
|
||||||
|
</File>
|
||||||
</Files>
|
</Files>
|
||||||
<Globals>
|
<Globals>
|
||||||
</Globals>
|
</Globals>
|
||||||
|
|||||||
@@ -1,15 +1,18 @@
|
|||||||
<?xml version="1.0" encoding = "Windows-1252"?>
|
<?xml version="1.0" encoding="Windows-1252"?>
|
||||||
<VisualStudioProject
|
<VisualStudioProject
|
||||||
ProjectType="Visual C++"
|
ProjectType="Visual C++"
|
||||||
Version="8.00"
|
Version="8.00"
|
||||||
Name="libbulletdynamics"
|
Name="libbulletdynamics"
|
||||||
ProjectGUID="{61BD1097-CF2E-B296-DAA9-73A6FE135319}"
|
ProjectGUID="{61BD1097-CF2E-B296-DAA9-73A6FE135319}"
|
||||||
SccProjectName=""
|
RootNamespace="libbulletdynamics"
|
||||||
SccLocalPath="">
|
>
|
||||||
<Platforms>
|
<Platforms>
|
||||||
<Platform
|
<Platform
|
||||||
Name="Win32"/>
|
Name="Win32"
|
||||||
|
/>
|
||||||
</Platforms>
|
</Platforms>
|
||||||
|
<ToolFiles>
|
||||||
|
</ToolFiles>
|
||||||
<Configurations>
|
<Configurations>
|
||||||
<Configuration
|
<Configuration
|
||||||
Name="Release|Win32"
|
Name="Release|Win32"
|
||||||
@@ -17,72 +20,82 @@
|
|||||||
IntermediateDirectory="..\..\out\release8\build\libbulletdynamics\"
|
IntermediateDirectory="..\..\out\release8\build\libbulletdynamics\"
|
||||||
ConfigurationType="4"
|
ConfigurationType="4"
|
||||||
UseOfMFC="0"
|
UseOfMFC="0"
|
||||||
ATLMinimizesCRunTimeLibraryUsage="FALSE">
|
ATLMinimizesCRunTimeLibraryUsage="false"
|
||||||
|
>
|
||||||
|
<Tool
|
||||||
|
Name="VCPreBuildEventTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCCustomBuildTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCXMLDataGeneratorTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCWebServiceProxyGeneratorTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCMIDLTool"
|
||||||
|
PreprocessorDefinitions="NDEBUG;_LIB;_WINDOWS"
|
||||||
|
MkTypLibCompatible="true"
|
||||||
|
SuppressStartupBanner="true"
|
||||||
|
TargetEnvironment="1"
|
||||||
|
TypeLibraryName="..\..\out\release8\build\libbulletdynamics\libbulletdynamics.tlb"
|
||||||
|
/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCCLCompilerTool"
|
Name="VCCLCompilerTool"
|
||||||
Optimization="2"
|
|
||||||
StringPooling="TRUE"
|
|
||||||
EnableFunctionLevelLinking="TRUE"
|
|
||||||
RuntimeLibrary="2"
|
|
||||||
DebugInformationFormat="3"
|
|
||||||
BufferSecurityCheck="FALSE"
|
|
||||||
PreprocessorDefinitions="NDEBUG;_LIB;_WINDOWS;WIN32"
|
|
||||||
OptimizeForProcessor="1"
|
|
||||||
ExceptionHandling="0"
|
|
||||||
AdditionalOptions=" "
|
AdditionalOptions=" "
|
||||||
|
Optimization="2"
|
||||||
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"
|
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"
|
||||||
|
PreprocessorDefinitions="NDEBUG;_LIB;_WINDOWS;WIN32"
|
||||||
|
StringPooling="true"
|
||||||
|
ExceptionHandling="0"
|
||||||
|
RuntimeLibrary="2"
|
||||||
|
BufferSecurityCheck="false"
|
||||||
|
EnableFunctionLevelLinking="true"
|
||||||
|
TreatWChar_tAsBuiltInType="false"
|
||||||
PrecompiledHeaderFile="..\..\out\release8\build\libbulletdynamics\libbulletdynamics.pch"
|
PrecompiledHeaderFile="..\..\out\release8\build\libbulletdynamics\libbulletdynamics.pch"
|
||||||
AssemblerListingLocation="..\..\out\release8\build\libbulletdynamics\"
|
AssemblerListingLocation="..\..\out\release8\build\libbulletdynamics\"
|
||||||
ObjectFile="..\..\out\release8\build\libbulletdynamics\"
|
ObjectFile="..\..\out\release8\build\libbulletdynamics\"
|
||||||
ProgramDataBaseFileName="..\..\out\release8\build\libbulletdynamics\bulletdynamics.pdb"
|
ProgramDataBaseFileName="..\..\out\release8\build\libbulletdynamics\bulletdynamics.pdb"
|
||||||
WarningLevel="3"
|
WarningLevel="3"
|
||||||
SuppressStartupBanner="TRUE"
|
SuppressStartupBanner="true"
|
||||||
Detect64BitPortabilityProblems="TRUE"
|
Detect64BitPortabilityProblems="true"
|
||||||
TreatWChar_tAsBuiltInType="false"
|
DebugInformationFormat="3"
|
||||||
CompileAs="0"/>
|
CompileAs="0"
|
||||||
<Tool
|
|
||||||
Name="VCCustomBuildTool"/>
|
|
||||||
<Tool
|
|
||||||
Name="VCLinkerTool"
|
|
||||||
LinkIncremental="1"
|
|
||||||
OptimizeReferences="2"
|
|
||||||
EnableCOMDATFolding="2"
|
|
||||||
GenerateDebugInformation="TRUE"
|
|
||||||
IgnoreDefaultLibraryNames="LIBC,LIBCD,LIBCMT,LIBCMTD"
|
|
||||||
AdditionalOptions=" "
|
|
||||||
AdditionalDependencies=""
|
|
||||||
IgnoreImportLibrary="TRUE"
|
|
||||||
SuppressStartupBanner="TRUE"
|
|
||||||
AdditionalLibraryDirectories=""
|
|
||||||
ProgramDatabaseFile="..\..\out\release8\build\libbulletdynamics\bulletdynamics.pdb"
|
|
||||||
TargetMachine="1"/>
|
|
||||||
<Tool
|
|
||||||
Name="VCLibrarianTool"
|
|
||||||
OutputFile="..\..\out\release8\libs\libbulletdynamics.lib"
|
|
||||||
SuppressStartupBanner="TRUE"/>
|
|
||||||
<Tool
|
|
||||||
Name="VCMIDLTool"
|
|
||||||
PreprocessorDefinitions="NDEBUG;_LIB;_WINDOWS"
|
|
||||||
MkTypLibCompatible="TRUE"
|
|
||||||
SuppressStartupBanner="TRUE"
|
|
||||||
TargetEnvironment="1"
|
|
||||||
TypeLibraryName="..\..\out\release8\build\libbulletdynamics\libbulletdynamics.tlb"/>
|
|
||||||
<Tool
|
|
||||||
Name="VCPostBuildEventTool"
|
|
||||||
/>
|
/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCPreBuildEventTool"/>
|
Name="VCManagedResourceCompilerTool"
|
||||||
<Tool
|
/>
|
||||||
Name="VCPreLinkEventTool"/>
|
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCResourceCompilerTool"
|
Name="VCResourceCompilerTool"
|
||||||
PreprocessorDefinitions="NDEBUG;_LIB;_WINDOWS;PROJECTGEN_VERSION=8"
|
PreprocessorDefinitions="NDEBUG;_LIB;_WINDOWS;PROJECTGEN_VERSION=8"
|
||||||
|
Culture="1033"
|
||||||
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"
|
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"
|
||||||
Culture="1033"/>
|
/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCWebServiceProxyGeneratorTool"/>
|
Name="VCPreLinkEventTool"
|
||||||
|
/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCWebDeploymentTool"/>
|
Name="VCLibrarianTool"
|
||||||
|
OutputFile="..\..\out\release8\libs\libbulletdynamics.lib"
|
||||||
|
SuppressStartupBanner="true"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCALinkTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCXDCMakeTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCBscMakeTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCFxCopTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCPostBuildEventTool"
|
||||||
|
/>
|
||||||
</Configuration>
|
</Configuration>
|
||||||
<Configuration
|
<Configuration
|
||||||
Name="Debug|Win32"
|
Name="Debug|Win32"
|
||||||
@@ -90,156 +103,204 @@
|
|||||||
IntermediateDirectory="..\..\out\debug8\build\libbulletdynamics\"
|
IntermediateDirectory="..\..\out\debug8\build\libbulletdynamics\"
|
||||||
ConfigurationType="4"
|
ConfigurationType="4"
|
||||||
UseOfMFC="0"
|
UseOfMFC="0"
|
||||||
ATLMinimizesCRunTimeLibraryUsage="FALSE">
|
ATLMinimizesCRunTimeLibraryUsage="false"
|
||||||
|
>
|
||||||
|
<Tool
|
||||||
|
Name="VCPreBuildEventTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCCustomBuildTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCXMLDataGeneratorTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCWebServiceProxyGeneratorTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCMIDLTool"
|
||||||
|
PreprocessorDefinitions="_DEBUG;_LIB;_WINDOWS"
|
||||||
|
MkTypLibCompatible="true"
|
||||||
|
SuppressStartupBanner="true"
|
||||||
|
TargetEnvironment="1"
|
||||||
|
TypeLibraryName="..\..\out\debug8\build\libbulletdynamics\libbulletdynamics.tlb"
|
||||||
|
/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCCLCompilerTool"
|
Name="VCCLCompilerTool"
|
||||||
Optimization="0"
|
|
||||||
MinimalRebuild="TRUE"
|
|
||||||
DebugInformationFormat="4"
|
|
||||||
RuntimeTypeInfo="TRUE"
|
|
||||||
RuntimeLibrary="3"
|
|
||||||
PreprocessorDefinitions="_DEBUG;_LIB;_WINDOWS;WIN32"
|
|
||||||
OptimizeForProcessor="1"
|
|
||||||
ExceptionHandling="0"
|
|
||||||
AdditionalOptions=" "
|
AdditionalOptions=" "
|
||||||
|
Optimization="0"
|
||||||
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"
|
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"
|
||||||
|
PreprocessorDefinitions="_DEBUG;_LIB;_WINDOWS;WIN32"
|
||||||
|
MinimalRebuild="true"
|
||||||
|
ExceptionHandling="0"
|
||||||
|
RuntimeLibrary="3"
|
||||||
|
TreatWChar_tAsBuiltInType="false"
|
||||||
|
RuntimeTypeInfo="true"
|
||||||
PrecompiledHeaderFile="..\..\out\debug8\build\libbulletdynamics\libbulletdynamics.pch"
|
PrecompiledHeaderFile="..\..\out\debug8\build\libbulletdynamics\libbulletdynamics.pch"
|
||||||
AssemblerListingLocation="..\..\out\debug8\build\libbulletdynamics\"
|
AssemblerListingLocation="..\..\out\debug8\build\libbulletdynamics\"
|
||||||
ObjectFile="..\..\out\debug8\build\libbulletdynamics\"
|
ObjectFile="..\..\out\debug8\build\libbulletdynamics\"
|
||||||
ProgramDataBaseFileName="..\..\out\debug8\build\libbulletdynamics\bulletdynamics.pdb"
|
ProgramDataBaseFileName="..\..\out\debug8\build\libbulletdynamics\bulletdynamics.pdb"
|
||||||
WarningLevel="3"
|
WarningLevel="3"
|
||||||
SuppressStartupBanner="TRUE"
|
SuppressStartupBanner="true"
|
||||||
Detect64BitPortabilityProblems="TRUE"
|
Detect64BitPortabilityProblems="true"
|
||||||
TreatWChar_tAsBuiltInType="false"
|
DebugInformationFormat="4"
|
||||||
CompileAs="0"/>
|
CompileAs="0"
|
||||||
<Tool
|
|
||||||
Name="VCCustomBuildTool"/>
|
|
||||||
<Tool
|
|
||||||
Name="VCLinkerTool"
|
|
||||||
LinkIncremental="2"
|
|
||||||
GenerateDebugInformation="TRUE"
|
|
||||||
IgnoreDefaultLibraryNames="LIBC,LIBCD,LIBCMT,LIBCMTD,MSVCRT"
|
|
||||||
AdditionalOptions=" "
|
|
||||||
AdditionalDependencies=""
|
|
||||||
IgnoreImportLibrary="TRUE"
|
|
||||||
SuppressStartupBanner="TRUE"
|
|
||||||
AdditionalLibraryDirectories=""
|
|
||||||
ProgramDatabaseFile="..\..\out\debug8\build\libbulletdynamics\bulletdynamics.pdb"
|
|
||||||
TargetMachine="1"/>
|
|
||||||
<Tool
|
|
||||||
Name="VCLibrarianTool"
|
|
||||||
OutputFile="..\..\out\debug8\libs\libbulletdynamics_d.lib"
|
|
||||||
SuppressStartupBanner="TRUE"/>
|
|
||||||
<Tool
|
|
||||||
Name="VCMIDLTool"
|
|
||||||
PreprocessorDefinitions="_DEBUG;_LIB;_WINDOWS"
|
|
||||||
MkTypLibCompatible="TRUE"
|
|
||||||
SuppressStartupBanner="TRUE"
|
|
||||||
TargetEnvironment="1"
|
|
||||||
TypeLibraryName="..\..\out\debug8\build\libbulletdynamics\libbulletdynamics.tlb"/>
|
|
||||||
<Tool
|
|
||||||
Name="VCPostBuildEventTool"
|
|
||||||
/>
|
/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCPreBuildEventTool"/>
|
Name="VCManagedResourceCompilerTool"
|
||||||
<Tool
|
/>
|
||||||
Name="VCPreLinkEventTool"/>
|
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCResourceCompilerTool"
|
Name="VCResourceCompilerTool"
|
||||||
PreprocessorDefinitions="_DEBUG;_LIB;_WINDOWS;PROJECTGEN_VERSION=8"
|
PreprocessorDefinitions="_DEBUG;_LIB;_WINDOWS;PROJECTGEN_VERSION=8"
|
||||||
|
Culture="1033"
|
||||||
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"
|
AdditionalIncludeDirectories=".;..\..;..\..\Bullet;..\..\BulletDynamics;..\..\LinearMath"
|
||||||
Culture="1033"/>
|
/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCWebServiceProxyGeneratorTool"/>
|
Name="VCPreLinkEventTool"
|
||||||
|
/>
|
||||||
<Tool
|
<Tool
|
||||||
Name="VCWebDeploymentTool"/>
|
Name="VCLibrarianTool"
|
||||||
|
OutputFile="..\..\out\debug8\libs\libbulletdynamics_d.lib"
|
||||||
|
SuppressStartupBanner="true"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCALinkTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCXDCMakeTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCBscMakeTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCFxCopTool"
|
||||||
|
/>
|
||||||
|
<Tool
|
||||||
|
Name="VCPostBuildEventTool"
|
||||||
|
/>
|
||||||
</Configuration>
|
</Configuration>
|
||||||
</Configurations>
|
</Configurations>
|
||||||
|
<References>
|
||||||
|
</References>
|
||||||
<Files>
|
<Files>
|
||||||
<Filter
|
<Filter
|
||||||
Name="Source Files"
|
Name="Source Files"
|
||||||
Filter="">
|
>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactConstraint.cpp">
|
RelativePath="..\..\BulletDynamics\Dynamics\BU_Joint.cpp"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\HingeConstraint.cpp">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactConstraint.cpp"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\OdeConstraintSolver.cpp">
|
RelativePath="..\..\BulletDynamics\Dynamics\ContactJoint.cpp"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\Point2PointConstraint.cpp">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\Generic6DofConstraint.cpp"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\SimpleConstraintSolver.cpp">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\HingeConstraint.cpp"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\Solve2LinearConstraint.cpp">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\OdeConstraintSolver.cpp"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\SorLcp.cpp">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\Point2PointConstraint.cpp"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\TypedConstraint.cpp">
|
RelativePath="..\..\BulletDynamics\Dynamics\RigidBody.cpp"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\Dynamics\BU_Joint.cpp">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\SimpleConstraintSolver.cpp"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\Dynamics\ContactJoint.cpp">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\Solve2LinearConstraint.cpp"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\Dynamics\RigidBody.cpp">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\SorLcp.cpp"
|
||||||
|
>
|
||||||
|
</File>
|
||||||
|
<File
|
||||||
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\TypedConstraint.cpp"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
</Filter>
|
</Filter>
|
||||||
<Filter
|
<Filter
|
||||||
Name="Header Files"
|
Name="Header Files"
|
||||||
Filter="">
|
>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\ConstraintSolver.h">
|
RelativePath="..\..\BulletDynamics\Dynamics\BU_Joint.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactConstraint.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\ConstraintSolver.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactSolverInfo.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactConstraint.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\HingeConstraint.h">
|
RelativePath="..\..\BulletDynamics\Dynamics\ContactJoint.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\JacobianEntry.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\ContactSolverInfo.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\OdeConstraintSolver.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\Generic6DofConstraint.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\Point2PointConstraint.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\HingeConstraint.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\SimpleConstraintSolver.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\JacobianEntry.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\Solve2LinearConstraint.h">
|
RelativePath="..\..\BulletDynamics\Dynamics\MassProps.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\SorLcp.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\OdeConstraintSolver.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\ConstraintSolver\TypedConstraint.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\Point2PointConstraint.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\Dynamics\BU_Joint.h">
|
RelativePath="..\..\BulletDynamics\Dynamics\RigidBody.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\Dynamics\ContactJoint.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\SimpleConstraintSolver.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\Dynamics\MassProps.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\Solve2LinearConstraint.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
<File
|
<File
|
||||||
RelativePath="..\..\BulletDynamics\Dynamics\RigidBody.h">
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\SorLcp.h"
|
||||||
|
>
|
||||||
|
</File>
|
||||||
|
<File
|
||||||
|
RelativePath="..\..\BulletDynamics\ConstraintSolver\TypedConstraint.h"
|
||||||
|
>
|
||||||
</File>
|
</File>
|
||||||
</Filter>
|
</Filter>
|
||||||
</Files>
|
</Files>
|
||||||
|
|||||||
@@ -21,10 +21,6 @@ Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appCcdPhysicsDemo", "appCcd
|
|||||||
EndProject
|
EndProject
|
||||||
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appColladaDemo", "appColladaDemo.vcproj", "{D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}"
|
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appColladaDemo", "appColladaDemo.vcproj", "{D7BF5DDA-C097-9E8B-5EC1-40DE45FB46BF}"
|
||||||
ProjectSection(ProjectDependencies) = postProject
|
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}
|
{D7F466F4-2AEA-4648-BE09-024C887BC157} = {D7F466F4-2AEA-4648-BE09-024C887BC157}
|
||||||
{FF956BB3-F377-43A8-AB31-633299BDF6C6} = {FF956BB3-F377-43A8-AB31-633299BDF6C6}
|
{FF956BB3-F377-43A8-AB31-633299BDF6C6} = {FF956BB3-F377-43A8-AB31-633299BDF6C6}
|
||||||
{3D872CA6-782B-46C9-A336-1B18C0A4FBD5} = {3D872CA6-782B-46C9-A336-1B18C0A4FBD5}
|
{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}
|
{90F5975E-550B-EEC8-9A8A-B8581D3FCF97} = {90F5975E-550B-EEC8-9A8A-B8581D3FCF97}
|
||||||
{C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}
|
{C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E} = {C63CFD5B-23E8-FB4F-79DB-E40F463B0C1E}
|
||||||
{85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822}
|
{85BCCE3E-992B-B6D7-28F6-CF0A12680822} = {85BCCE3E-992B-B6D7-28F6-CF0A12680822}
|
||||||
{B70CBA1A-414C-4872-8DAF-31934BCAB568} = {B70CBA1A-414C-4872-8DAF-31934BCAB568}
|
{38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC} = {38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}
|
||||||
{4A974C64-D51F-4D0F-85B8-0C876EF29F2E} = {4A974C64-D51F-4D0F-85B8-0C876EF29F2E}
|
|
||||||
EndProjectSection
|
EndProjectSection
|
||||||
EndProject
|
EndProject
|
||||||
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "appCollisionDemo", "appCollisionDemo.vcproj", "{E70DB92E-C1F5-AE72-F9E2-DB9B4B3DBEC9}"
|
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}"
|
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "FCollada_vc8", "..\..\Extras\FCollada\FCollada_vc8.vcproj", "{FF956BB3-F377-43A8-AB31-633299BDF6C6}"
|
||||||
EndProject
|
EndProject
|
||||||
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "FColladaLib_vc8", "..\..\Extras\FCollada\FColladaLib_vc8.vcproj", "{5160A878-73A5-41CA-B8D5-C3D560DD1D58}"
|
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
|
EndProject
|
||||||
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "FMath_vc8", "..\..\Extras\FCollada\FMath\FMath_vc8.vcproj", "{38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}"
|
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "FMath_vc8", "..\..\Extras\FCollada\FMath\FMath_vc8.vcproj", "{38BB0C01-CF6E-44D7-8AE1-5F92D38DB1DC}"
|
||||||
EndProject
|
EndProject
|
||||||
@@ -216,16 +214,6 @@ Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "FUtils_vc8", "..\..\Extras\
|
|||||||
EndProject
|
EndProject
|
||||||
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "LibXML_vc8", "..\..\Extras\FCollada\LibXML\LibXML_vc8.vcproj", "{D7F466F4-2AEA-4648-BE09-024C887BC157}"
|
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "LibXML_vc8", "..\..\Extras\FCollada\LibXML\LibXML_vc8.vcproj", "{D7F466F4-2AEA-4648-BE09-024C887BC157}"
|
||||||
EndProject
|
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
|
Global
|
||||||
GlobalSection(SolutionConfigurationPlatforms) = preSolution
|
GlobalSection(SolutionConfigurationPlatforms) = preSolution
|
||||||
Debug DLL|Win32 = Debug DLL|Win32
|
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(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.ActiveCfg = Release|Win32
|
||||||
{D7F466F4-2AEA-4648-BE09-024C887BC157}.Release|Win32.Build.0 = 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
|
EndGlobalSection
|
||||||
GlobalSection(SolutionProperties) = preSolution
|
GlobalSection(SolutionProperties) = preSolution
|
||||||
HideSolutionNode = FALSE
|
HideSolutionNode = FALSE
|
||||||
|
|||||||
Reference in New Issue
Block a user