mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 13:20:07 +00:00
fixes in build system
This commit is contained in:
parent
7a833a7ac2
commit
938db633df
@ -185,44 +185,51 @@ IF (WIN32)
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/Glew
|
||||
)
|
||||
IF (BUILD_SHARED_LIBS)
|
||||
TARGET_LINK_LIBRARIES(
|
||||
BulletExampleBrowserLib Bullet3Common BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils
|
||||
BulletInverseDynamics LinearMath OpenGLWindow gwen
|
||||
${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY}
|
||||
)
|
||||
ENDIF (BUILD_SHARED_LIBS)
|
||||
ADD_DEFINITIONS(-DGLEW_STATIC)
|
||||
ADD_DEFINITIONS(-DGLEW_STATIC)
|
||||
ELSE(WIN32)
|
||||
IF(APPLE)
|
||||
find_library(COCOA NAMES Cocoa)
|
||||
MESSAGE(${COCOA})
|
||||
IF (BUILD_SHARED_LIBS)
|
||||
TARGET_LINK_LIBRARIES(
|
||||
BulletExampleBrowserLib Bullet3Common BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils
|
||||
BulletInverseDynamics LinearMath OpenGLWindow gwen
|
||||
${COCOA} ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY}
|
||||
)
|
||||
ELSE(APPLE)
|
||||
ENDIF (BUILD_SHARED_LIBS)
|
||||
ELSE(APPLE)
|
||||
ADD_DEFINITIONS("-DGLEW_INIT_OPENGL11_FUNCTIONS=1")
|
||||
ADD_DEFINITIONS("-DGLEW_STATIC")
|
||||
ADD_DEFINITIONS("-DGLEW_DYNAMIC_LOAD_ALL_GLX_FUNCTIONS=1")
|
||||
INCLUDE_DIRECTORIES( ${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/Glew )
|
||||
IF (BUILD_SHARED_LIBS)
|
||||
TARGET_LINK_LIBRARIES(
|
||||
BulletExampleBrowserLib Bullet3Common BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils
|
||||
BulletInverseDynamics LinearMath OpenGLWindow gwen
|
||||
pthread dl
|
||||
)
|
||||
ENDIF(BUILD_SHARED_LIBS)
|
||||
ENDIF(APPLE)
|
||||
ENDIF(APPLE)
|
||||
ENDIF(WIN32)
|
||||
|
||||
|
||||
ADD_LIBRARY(BulletExampleBrowserLib ${BulletExampleBrowser_SRCS} )
|
||||
SET_TARGET_PROPERTIES(BulletExampleBrowserLib PROPERTIES VERSION ${BULLET_VERSION})
|
||||
SET_TARGET_PROPERTIES(BulletExampleBrowserLib PROPERTIES SOVERSION ${BULLET_VERSION})
|
||||
IF (BUILD_SHARED_LIBS)
|
||||
IF (WIN32)
|
||||
TARGET_LINK_LIBRARIES(
|
||||
BulletExampleBrowserLib Bullet3Common BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils
|
||||
BulletInverseDynamics LinearMath OpenGLWindow gwen
|
||||
${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY}
|
||||
)
|
||||
ELSE(WIN32)
|
||||
IF(APPLE)
|
||||
TARGET_LINK_LIBRARIES(
|
||||
BulletExampleBrowserLib Bullet3Common BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils
|
||||
BulletInverseDynamics LinearMath OpenGLWindow gwen
|
||||
${COCOA} ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY}
|
||||
)
|
||||
ELSE(APPLE)
|
||||
TARGET_LINK_LIBRARIES(
|
||||
BulletExampleBrowserLib Bullet3Common BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils
|
||||
BulletInverseDynamics LinearMath OpenGLWindow gwen
|
||||
pthread dl
|
||||
)
|
||||
ENDIF(APPLE)
|
||||
ENDIF(WIN32)
|
||||
ENDIF(BUILD_SHARED_LIBS)
|
||||
|
||||
####################
|
||||
#
|
||||
# Bullet Example Browser main app
|
||||
#
|
||||
####################
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
.
|
||||
|
@ -274,17 +274,17 @@ struct ExampleEntriesInternalData
|
||||
btAlignedObjectArray<ExampleEntry> m_allExamples;
|
||||
};
|
||||
|
||||
ExampleEntries::ExampleEntries()
|
||||
ExampleEntriesAll::ExampleEntriesAll()
|
||||
{
|
||||
m_data = new ExampleEntriesInternalData;
|
||||
}
|
||||
|
||||
ExampleEntries::~ExampleEntries()
|
||||
ExampleEntriesAll::~ExampleEntriesAll()
|
||||
{
|
||||
delete m_data;
|
||||
}
|
||||
|
||||
void ExampleEntries::initOpenCLExampleEntries()
|
||||
void ExampleEntriesAll::initOpenCLExampleEntries()
|
||||
{
|
||||
#ifdef B3_USE_CLEW
|
||||
#ifndef NO_OPENGL3
|
||||
@ -297,7 +297,7 @@ void ExampleEntries::initOpenCLExampleEntries()
|
||||
#endif //B3_USE_CLEW
|
||||
}
|
||||
|
||||
void ExampleEntries::initExampleEntries()
|
||||
void ExampleEntriesAll::initExampleEntries()
|
||||
{
|
||||
m_data->m_allExamples.clear();
|
||||
|
||||
@ -330,33 +330,33 @@ void ExampleEntries::initExampleEntries()
|
||||
|
||||
}
|
||||
|
||||
void ExampleEntries::registerExampleEntry(int menuLevel, const char* name,const char* description, CommonExampleInterface::CreateFunc* createFunc, int option)
|
||||
void ExampleEntriesAll::registerExampleEntry(int menuLevel, const char* name,const char* description, CommonExampleInterface::CreateFunc* createFunc, int option)
|
||||
{
|
||||
ExampleEntry e( menuLevel,name,description, createFunc, option);
|
||||
gAdditionalRegisteredExamples.push_back(e);
|
||||
}
|
||||
|
||||
int ExampleEntries::getNumRegisteredExamples()
|
||||
int ExampleEntriesAll::getNumRegisteredExamples()
|
||||
{
|
||||
return m_data->m_allExamples.size();
|
||||
}
|
||||
|
||||
CommonExampleInterface::CreateFunc* ExampleEntries::getExampleCreateFunc(int index)
|
||||
CommonExampleInterface::CreateFunc* ExampleEntriesAll::getExampleCreateFunc(int index)
|
||||
{
|
||||
return m_data->m_allExamples[index].m_createFunc;
|
||||
}
|
||||
|
||||
int ExampleEntries::getExampleOption(int index)
|
||||
int ExampleEntriesAll::getExampleOption(int index)
|
||||
{
|
||||
return m_data->m_allExamples[index].m_option;
|
||||
}
|
||||
|
||||
const char* ExampleEntries::getExampleName(int index)
|
||||
const char* ExampleEntriesAll::getExampleName(int index)
|
||||
{
|
||||
return m_data->m_allExamples[index].m_name;
|
||||
}
|
||||
|
||||
const char* ExampleEntries::getExampleDescription(int index)
|
||||
const char* ExampleEntriesAll::getExampleDescription(int index)
|
||||
{
|
||||
return m_data->m_allExamples[index].m_description;
|
||||
}
|
||||
|
@ -6,32 +6,56 @@
|
||||
|
||||
|
||||
|
||||
|
||||
class ExampleEntries
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
virtual ~ExampleEntries() {}
|
||||
|
||||
|
||||
virtual void initExampleEntries()=0;
|
||||
|
||||
virtual void initOpenCLExampleEntries()=0;
|
||||
|
||||
virtual int getNumRegisteredExamples()=0;
|
||||
|
||||
virtual CommonExampleInterface::CreateFunc* getExampleCreateFunc(int index)=0;
|
||||
|
||||
virtual const char* getExampleName(int index)=0;
|
||||
|
||||
virtual const char* getExampleDescription(int index)=0;
|
||||
|
||||
virtual int getExampleOption(int index)=0;
|
||||
|
||||
};
|
||||
|
||||
|
||||
class ExampleEntriesAll : public ExampleEntries
|
||||
{
|
||||
|
||||
struct ExampleEntriesInternalData* m_data;
|
||||
|
||||
public:
|
||||
|
||||
ExampleEntries();
|
||||
virtual ~ExampleEntries();
|
||||
ExampleEntriesAll();
|
||||
virtual ~ExampleEntriesAll();
|
||||
|
||||
static void registerExampleEntry(int menuLevel, const char* name,const char* description, CommonExampleInterface::CreateFunc* createFunc, int option=0);
|
||||
|
||||
void initExampleEntries();
|
||||
virtual void initExampleEntries();
|
||||
|
||||
void initOpenCLExampleEntries();
|
||||
virtual void initOpenCLExampleEntries();
|
||||
|
||||
int getNumRegisteredExamples();
|
||||
virtual int getNumRegisteredExamples();
|
||||
|
||||
CommonExampleInterface::CreateFunc* getExampleCreateFunc(int index);
|
||||
virtual CommonExampleInterface::CreateFunc* getExampleCreateFunc(int index);
|
||||
|
||||
const char* getExampleName(int index);
|
||||
virtual const char* getExampleName(int index);
|
||||
|
||||
const char* getExampleDescription(int index);
|
||||
virtual const char* getExampleDescription(int index);
|
||||
|
||||
int getExampleOption(int index);
|
||||
virtual int getExampleOption(int index);
|
||||
|
||||
};
|
||||
|
||||
|
@ -25,6 +25,143 @@ void* ExampleBrowserMemoryFunc();
|
||||
#ifndef _WIN32
|
||||
#include "../MultiThreading/b3PosixThreadSupport.h"
|
||||
|
||||
#include "ExampleEntries.h"
|
||||
#include "LinearMath/btAlignedObjectArray.h"
|
||||
#include "EmptyExample.h"
|
||||
|
||||
#include "../SharedMemory/PhysicsServerExample.h"
|
||||
#include "../SharedMemory/PhysicsClientExample.h"
|
||||
|
||||
|
||||
|
||||
|
||||
class ExampleEntriesPhysicsServer : public ExampleEntries
|
||||
{
|
||||
|
||||
struct ExampleEntriesInternalData2* m_data;
|
||||
|
||||
public:
|
||||
|
||||
ExampleEntriesPhysicsServer();
|
||||
virtual ~ExampleEntriesPhysicsServer();
|
||||
|
||||
static void registerExampleEntry(int menuLevel, const char* name,const char* description, CommonExampleInterface::CreateFunc* createFunc, int option=0);
|
||||
|
||||
virtual void initExampleEntries();
|
||||
|
||||
virtual void initOpenCLExampleEntries();
|
||||
|
||||
virtual int getNumRegisteredExamples();
|
||||
|
||||
virtual CommonExampleInterface::CreateFunc* getExampleCreateFunc(int index);
|
||||
|
||||
virtual const char* getExampleName(int index);
|
||||
|
||||
virtual const char* getExampleDescription(int index);
|
||||
|
||||
virtual int getExampleOption(int index);
|
||||
|
||||
};
|
||||
|
||||
|
||||
struct ExampleEntryPhysicsServer
|
||||
{
|
||||
int m_menuLevel;
|
||||
const char* m_name;
|
||||
const char* m_description;
|
||||
CommonExampleInterface::CreateFunc* m_createFunc;
|
||||
int m_option;
|
||||
|
||||
ExampleEntryPhysicsServer(int menuLevel, const char* name)
|
||||
:m_menuLevel(menuLevel), m_name(name), m_description(0), m_createFunc(0), m_option(0)
|
||||
{
|
||||
}
|
||||
|
||||
ExampleEntryPhysicsServer(int menuLevel, const char* name,const char* description, CommonExampleInterface::CreateFunc* createFunc, int option=0)
|
||||
:m_menuLevel(menuLevel), m_name(name), m_description(description), m_createFunc(createFunc), m_option(option)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
struct ExampleEntriesInternalData2
|
||||
{
|
||||
btAlignedObjectArray<ExampleEntryPhysicsServer> m_allExamples;
|
||||
};
|
||||
|
||||
static ExampleEntryPhysicsServer gDefaultExamplesPhysicsServer[]=
|
||||
{
|
||||
|
||||
ExampleEntryPhysicsServer(0,"Robotics Control"),
|
||||
|
||||
ExampleEntryPhysicsServer(1,"Physics Server", "Create a physics server that communicates with a physics client over shared memory",
|
||||
PhysicsServerCreateFunc),
|
||||
ExampleEntryPhysicsServer(1,"Physics Server (Logging)", "Create a physics server that communicates with a physics client over shared memory. It will log all commands to a file.",
|
||||
PhysicsServerCreateFunc,PHYSICS_SERVER_ENABLE_COMMAND_LOGGING),
|
||||
ExampleEntryPhysicsServer(1,"Physics Server (Replay Log)", "Create a physics server that replay a command log from disk.",
|
||||
PhysicsServerCreateFunc,PHYSICS_SERVER_REPLAY_FROM_COMMAND_LOG),
|
||||
|
||||
ExampleEntryPhysicsServer(1, "Physics Client", "Create a physics client that can communicate with a physics server over shared memory", PhysicsClientCreateFunc),
|
||||
|
||||
};
|
||||
|
||||
|
||||
ExampleEntriesPhysicsServer::ExampleEntriesPhysicsServer()
|
||||
{
|
||||
m_data = new ExampleEntriesInternalData2;
|
||||
}
|
||||
|
||||
ExampleEntriesPhysicsServer::~ExampleEntriesPhysicsServer()
|
||||
{
|
||||
delete m_data;
|
||||
}
|
||||
|
||||
void ExampleEntriesPhysicsServer::initOpenCLExampleEntries()
|
||||
{
|
||||
}
|
||||
|
||||
void ExampleEntriesPhysicsServer::initExampleEntries()
|
||||
{
|
||||
m_data->m_allExamples.clear();
|
||||
|
||||
|
||||
|
||||
int numDefaultEntries = sizeof(gDefaultExamplesPhysicsServer)/sizeof(ExampleEntryPhysicsServer);
|
||||
for (int i=0;i<numDefaultEntries;i++)
|
||||
{
|
||||
m_data->m_allExamples.push_back(gDefaultExamplesPhysicsServer[i]);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void ExampleEntriesPhysicsServer::registerExampleEntry(int menuLevel, const char* name,const char* description, CommonExampleInterface::CreateFunc* createFunc, int option)
|
||||
{
|
||||
}
|
||||
|
||||
int ExampleEntriesPhysicsServer::getNumRegisteredExamples()
|
||||
{
|
||||
return m_data->m_allExamples.size();
|
||||
}
|
||||
|
||||
CommonExampleInterface::CreateFunc* ExampleEntriesPhysicsServer::getExampleCreateFunc(int index)
|
||||
{
|
||||
return m_data->m_allExamples[index].m_createFunc;
|
||||
}
|
||||
|
||||
int ExampleEntriesPhysicsServer::getExampleOption(int index)
|
||||
{
|
||||
return m_data->m_allExamples[index].m_option;
|
||||
}
|
||||
|
||||
const char* ExampleEntriesPhysicsServer::getExampleName(int index)
|
||||
{
|
||||
return m_data->m_allExamples[index].m_name;
|
||||
}
|
||||
|
||||
const char* ExampleEntriesPhysicsServer::getExampleDescription(int index)
|
||||
{
|
||||
return m_data->m_allExamples[index].m_description;
|
||||
}
|
||||
|
||||
static b3ThreadSupportInterface* createExampleBrowserThreadSupport(int numThreads)
|
||||
{
|
||||
b3PosixThreadSupport::ThreadConstructionInfo constructionInfo("testThreads",
|
||||
@ -91,7 +228,7 @@ void ExampleBrowserThreadFunc(void* userPtr,void* lsMemory)
|
||||
b3Clock clock;
|
||||
|
||||
|
||||
ExampleEntries examples;
|
||||
ExampleEntriesPhysicsServer examples;
|
||||
examples.initExampleEntries();
|
||||
|
||||
DefaultBrowser* exampleBrowser = new DefaultBrowser(&examples);
|
||||
@ -231,7 +368,7 @@ void btShutDownExampleBrowser(btInProcessExampleBrowserInternalData* data)
|
||||
|
||||
struct btInProcessExampleBrowserMainThreadInternalData
|
||||
{
|
||||
ExampleEntries m_examples;
|
||||
ExampleEntriesPhysicsServer m_examples;
|
||||
DefaultBrowser* m_exampleBrowser;
|
||||
SharedMemoryInterface* m_sharedMem;
|
||||
b3Clock m_clock;
|
||||
|
@ -22,7 +22,7 @@ int main(int argc, char* argv[])
|
||||
b3Clock clock;
|
||||
|
||||
|
||||
ExampleEntries examples;
|
||||
ExampleEntriesAll examples;
|
||||
examples.initExampleEntries();
|
||||
|
||||
ExampleBrowserInterface* exampleBrowser = new DefaultBrowser(&examples);
|
||||
|
@ -18,7 +18,7 @@ ADD_LIBRARY(pybullet ${pybullet_SRCS})
|
||||
SET_TARGET_PROPERTIES(pybullet PROPERTIES VERSION ${BULLET_VERSION})
|
||||
SET_TARGET_PROPERTIES(pybullet PROPERTIES SOVERSION ${BULLET_VERSION})
|
||||
|
||||
TARGET_LINK_LIBRARIES(pybullet BulletExampleBrowserLib BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen Bullet3Common)
|
||||
TARGET_LINK_LIBRARIES(pybullet BulletExampleBrowserLib BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen Bullet3Common Python)
|
||||
ENDIF (BUILD_SHARED_LIBS)
|
||||
|
||||
|
||||
|
@ -138,6 +138,8 @@ pybullet_resetSimulation(PyObject* self, PyObject* args)
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, b3InitResetSimulationCommand(sm));
|
||||
// ASSERT_EQ(b3GetStatusType(statusHandle), CMD_RESET_SIMULATION_COMPLETED);
|
||||
}
|
||||
return PyLong_FromLong(1);
|
||||
|
||||
}
|
||||
|
||||
static PyMethodDef SpamMethods[] = {
|
||||
|
Loading…
Reference in New Issue
Block a user