premake build system fixes
This commit is contained in:
@@ -219,7 +219,7 @@ ENDIF (USE_DOUBLE_PRECISION)
|
||||
|
||||
IF (NOT USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD)
|
||||
ADD_DEFINITIONS(-DSKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD)
|
||||
ENDIF (USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD)
|
||||
ENDIF ()
|
||||
|
||||
IF(USE_GRAPHICAL_BENCHMARK)
|
||||
ADD_DEFINITIONS( -DUSE_GRAPHICAL_BENCHMARK)
|
||||
|
||||
@@ -44,7 +44,7 @@ public:
|
||||
void init() {
|
||||
this->createEmptyDynamicsWorld();
|
||||
m_dynamicsWorld->setGravity(m_gravity);
|
||||
BulletURDFImporter urdf_importer(&m_nogfx,0,1);
|
||||
BulletURDFImporter urdf_importer(&m_nogfx,0,1,0);
|
||||
URDFImporterInterface &u2b(urdf_importer);
|
||||
bool loadOk = u2b.loadURDF(m_filename.c_str(), m_base_fixed);
|
||||
|
||||
|
||||
@@ -187,7 +187,7 @@ void ImportSDFSetup::initPhysics()
|
||||
m_dynamicsWorld->setGravity(gravity);
|
||||
|
||||
|
||||
BulletURDFImporter u2b(m_guiHelper, 0,1);
|
||||
BulletURDFImporter u2b(m_guiHelper, 0,1,0);
|
||||
|
||||
bool loadOk = u2b.loadSDF(m_fileName);
|
||||
|
||||
|
||||
@@ -23,7 +23,7 @@ class BulletURDFImporter : public URDFImporterInterface
|
||||
|
||||
public:
|
||||
|
||||
BulletURDFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter, double globalScaling, int flags);
|
||||
BulletURDFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter, double globalScaling=1, int flags=0);
|
||||
|
||||
virtual ~BulletURDFImporter();
|
||||
|
||||
|
||||
@@ -194,7 +194,9 @@ void ImportUrdfSetup::initPhysics()
|
||||
}
|
||||
|
||||
|
||||
BulletURDFImporter u2b(m_guiHelper, 0,1);
|
||||
int flags=0;
|
||||
double globalScaling=1;
|
||||
BulletURDFImporter u2b(m_guiHelper, 0,globalScaling,flags);
|
||||
|
||||
|
||||
bool loadOk = u2b.loadURDF(m_fileName);
|
||||
|
||||
@@ -156,7 +156,7 @@ void InverseDynamicsExample::initPhysics()
|
||||
|
||||
|
||||
|
||||
BulletURDFImporter u2b(m_guiHelper,0,1);
|
||||
BulletURDFImporter u2b(m_guiHelper,0,1,0);
|
||||
bool loadOk = u2b.loadURDF("kuka_iiwa/model.urdf");// lwr / kuka.urdf");
|
||||
if (loadOk)
|
||||
{
|
||||
|
||||
@@ -10,7 +10,7 @@ end
|
||||
includedirs {".","../../src", "../ThirdPartyLibs"}
|
||||
|
||||
links {
|
||||
"Bullet3Common","BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision", "LinearMath", "BussIK"
|
||||
"BulletSoftBody", "Bullet3Common","BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision", "LinearMath", "BussIK"
|
||||
}
|
||||
|
||||
language "C++"
|
||||
@@ -163,7 +163,7 @@ defines {"B3_USE_STANDALONE_EXAMPLE"}
|
||||
includedirs {"../../src", "../ThirdPartyLibs"}
|
||||
|
||||
links {
|
||||
"BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision", "LinearMath", "OpenGL_Window","Bullet3Common","BussIK"
|
||||
"BulletSoftBody", "BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision", "LinearMath", "OpenGL_Window","Bullet3Common","BussIK"
|
||||
}
|
||||
initOpenGL()
|
||||
initGlew()
|
||||
@@ -334,7 +334,7 @@ if os.is("Windows") then
|
||||
}
|
||||
|
||||
links {
|
||||
"BulletInverseDynamicsUtils", "BulletInverseDynamics","Bullet3Common", "BulletDynamics","BulletCollision", "LinearMath","OpenGL_Window","openvr_api","BussIK"
|
||||
"BulletSoftBody", "BulletInverseDynamicsUtils", "BulletInverseDynamics","Bullet3Common", "BulletDynamics","BulletCollision", "LinearMath","OpenGL_Window","openvr_api","BussIK"
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -62,7 +62,7 @@ defines { "NO_SHARED_MEMORY" }
|
||||
includedirs {"..","../../../src", "../../ThirdPartyLibs","../../ThirdPartyLibs/clsocket/src"}
|
||||
|
||||
links {
|
||||
"clsocket","Bullet3Common","BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision", "LinearMath", "BussIK"
|
||||
"clsocket","Bullet3Common","BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletSoftBody", "BulletDynamics","BulletCollision", "LinearMath", "BussIK"
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -61,7 +61,7 @@ defines { "NO_SHARED_MEMORY" }
|
||||
includedirs {"..","../../../src", "../../ThirdPartyLibs","../../ThirdPartyLibs/enet/include"}
|
||||
|
||||
links {
|
||||
"enet","Bullet3Common","BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision", "LinearMath", "BussIK"
|
||||
"enet","Bullet3Common","BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletSoftBody", "BulletDynamics","BulletCollision", "LinearMath", "BussIK"
|
||||
}
|
||||
|
||||
if os.is("Windows") then
|
||||
|
||||
@@ -152,7 +152,7 @@ project ("Test_PhysicsServerLoopBack")
|
||||
|
||||
includedirs {"../../src", "../../examples",
|
||||
"../../examples/ThirdPartyLibs"}
|
||||
defines {"PHYSICS_LOOP_BACK"}
|
||||
defines {"PHYSICS_LOOP_BACK", "SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD"}
|
||||
links {
|
||||
"BulletInverseDynamicsUtils",
|
||||
"BulletInverseDynamics",
|
||||
@@ -238,7 +238,7 @@ end
|
||||
|
||||
includedirs {"../../src", "../../examples",
|
||||
"../../examples/ThirdPartyLibs"}
|
||||
defines {"PHYSICS_SERVER_DIRECT"}
|
||||
defines {"PHYSICS_SERVER_DIRECT","SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD"}
|
||||
links {
|
||||
"BulletInverseDynamicsUtils",
|
||||
"BulletInverseDynamics",
|
||||
@@ -321,7 +321,7 @@ project ("Test_PhysicsServerInProcessExampleBrowser")
|
||||
|
||||
includedirs {"../../src", "../../examples",
|
||||
"../../examples/ThirdPartyLibs"}
|
||||
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
|
||||
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER", "SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD"}
|
||||
-- links {
|
||||
-- "BulletExampleBrowserLib",
|
||||
-- "BulletFileLoader",
|
||||
|
||||
Reference in New Issue
Block a user