Merge pull request #614 from erwincoumans/master
add BasicExampleGui for cmake, preliminary pybullet
This commit is contained in:
@@ -191,6 +191,7 @@ IF (APPLE)
|
||||
ENDIF()
|
||||
|
||||
OPTION(BUILD_BULLET3 "Set when you want to build Bullet 3" ON)
|
||||
OPTION(BUILD_PYBULLET "Set when you want to build pybullet (experimental Python bindings for Bullet)" OFF)
|
||||
|
||||
IF(BUILD_BULLET3)
|
||||
IF(APPLE)
|
||||
|
||||
@@ -1,10 +1,17 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="urdf_door">
|
||||
<link name="world"/>
|
||||
<joint name="fixed" type="fixed">
|
||||
<parent link="world"/>
|
||||
<child link="baseLink"/>
|
||||
<origin xyz="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<link name="baseLink">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.35"/>
|
||||
<mass value="0.0"/>
|
||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||
<mass value="1.0"/>
|
||||
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0.05 0 0.5"/>
|
||||
|
||||
@@ -29,3 +29,72 @@ IF (INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES)
|
||||
SET_TARGET_PROPERTIES(App_BasicExample PROPERTIES MINSIZEREL_POSTFIX "_MinsizeRel")
|
||||
SET_TARGET_PROPERTIES(App_BasicExample PROPERTIES RELWITHDEBINFO_POSTFIX "_RelWithDebugInfo")
|
||||
ENDIF(INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES)
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#################
|
||||
# Standalone BasicExampleGui using OpenGL (but not the example browser)
|
||||
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/btgui
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/Glew
|
||||
)
|
||||
|
||||
|
||||
SET(AppBasicExampleGui_SRCS
|
||||
BasicExample.cpp
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/build3/bullet.rc
|
||||
../StandaloneMain/main_opengl_single_example.cpp
|
||||
../ExampleBrowser/OpenGLGuiHelper.cpp
|
||||
../ExampleBrowser/GL_ShapeDrawer.cpp
|
||||
)
|
||||
|
||||
#this define maps StandaloneExampleCreateFunc to the right 'CreateFunc'
|
||||
ADD_DEFINITIONS(-DB3_USE_STANDALONE_EXAMPLE)
|
||||
|
||||
LINK_LIBRARIES(
|
||||
BulletDynamics BulletCollision LinearMath OpenGLWindow Bullet3Common ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY}
|
||||
)
|
||||
|
||||
#some code to support OpenGL and Glew cross platform
|
||||
IF (WIN32)
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/btgui/OpenGLWindow/GlewWindows
|
||||
)
|
||||
ADD_DEFINITIONS(-DGLEW_STATIC)
|
||||
ELSE(WIN32)
|
||||
IF(APPLE)
|
||||
find_library(COCOA NAMES Cocoa)
|
||||
MESSAGE(${COCOA})
|
||||
link_libraries(${COCOA})
|
||||
|
||||
ELSE(APPLE)
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/btgui/OpenGLWindow/GlewWindows
|
||||
)
|
||||
ADD_DEFINITIONS("-DGLEW_INIT_OPENGL11_FUNCTIONS=1")
|
||||
ADD_DEFINITIONS("-DGLEW_STATIC")
|
||||
ADD_DEFINITIONS("-DGLEW_DYNAMIC_LOAD_ALL_GLX_FUNCTIONS=1")
|
||||
|
||||
LINK_LIBRARIES( X11 pthread dl Xext)
|
||||
ENDIF(APPLE)
|
||||
ENDIF(WIN32)
|
||||
|
||||
|
||||
ADD_EXECUTABLE(AppBasicExampleGui
|
||||
${AppBasicExampleGui_SRCS}
|
||||
)
|
||||
|
||||
|
||||
IF (INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES)
|
||||
SET_TARGET_PROPERTIES(AppBasicExampleGui PROPERTIES DEBUG_POSTFIX "_Debug")
|
||||
SET_TARGET_PROPERTIES(AppBasicExampleGui PROPERTIES MINSIZEREL_POSTFIX "_MinsizeRel")
|
||||
SET_TARGET_PROPERTIES(AppBasicExampleGui PROPERTIES RELWITHDEBINFO_POSTFIX "_RelWithDebugInfo")
|
||||
ENDIF(INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES)
|
||||
|
||||
|
||||
|
||||
@@ -2,4 +2,6 @@ SUBDIRS( HelloWorld BasicDemo )
|
||||
IF(BUILD_BULLET3)
|
||||
SUBDIRS( ExampleBrowser ThirdPartyLibs/Gwen OpenGLWindow )
|
||||
ENDIF()
|
||||
|
||||
IF(BUILD_PYBULLET)
|
||||
SUBDIRS(pybullet)
|
||||
ENDIF(BUILD_PYBULLET)
|
||||
|
||||
@@ -120,6 +120,8 @@ class CommonWindowInterface
|
||||
virtual float getRetinaScale() const =0;
|
||||
virtual void setAllowRetina(bool allow) =0;
|
||||
|
||||
virtual int getWidth() const = 0;
|
||||
virtual int getHeight() const = 0;
|
||||
|
||||
virtual int fileOpenDialog(char* fileName, int maxFileNameLength) = 0;
|
||||
|
||||
|
||||
@@ -1,21 +1,19 @@
|
||||
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
.
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs
|
||||
)
|
||||
|
||||
FILE(GLOB ExampleBrowser_SRCS "*" "GwenGUISupport/*" )
|
||||
FILE(GLOB ExampleBrowser_HDRS "*" "GwenGUISupport/*" )
|
||||
FILE(GLOB GwenGUISupport_SRCS "GwenGUISupport/*" )
|
||||
FILE(GLOB GwenGUISupport_HDRS "GwenGUISupport/*" )
|
||||
|
||||
|
||||
|
||||
SET(App_ExampleBrowser_SRCS
|
||||
main.cpp
|
||||
ExampleEntries.cpp
|
||||
ExampleEntries.h
|
||||
SET(BulletExampleBrowser_SRCS
|
||||
OpenGLExampleBrowser.cpp
|
||||
OpenGLGuiHelper.cpp
|
||||
InProcessExampleBrowser.cpp
|
||||
GL_ShapeDrawer.cpp
|
||||
../SharedMemory/PhysicsServer.cpp
|
||||
../SharedMemory/PhysicsClientSharedMemory.cpp
|
||||
../SharedMemory/PhysicsClient.cpp
|
||||
@@ -97,8 +95,10 @@ SET(App_ExampleBrowser_SRCS
|
||||
|
||||
../../Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp
|
||||
../../Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp
|
||||
../../Extras/Serialize/BulletFileLoader/bChunk.cpp ../../Extras/Serialize/BulletFileLoader/bFile.cpp
|
||||
../../Extras/Serialize/BulletFileLoader/bDNA.cpp ../../Extras/Serialize/BulletFileLoader/btBulletFile.cpp
|
||||
../../Extras/Serialize/BulletFileLoader/bChunk.cpp
|
||||
../../Extras/Serialize/BulletFileLoader/bFile.cpp
|
||||
../../Extras/Serialize/BulletFileLoader/bDNA.cpp
|
||||
../../Extras/Serialize/BulletFileLoader/btBulletFile.cpp
|
||||
|
||||
../Importers/ImportBsp/BspLoader.h
|
||||
../Importers/ImportBsp/ImportBspExample.h
|
||||
@@ -168,42 +168,81 @@ SET(App_ExampleBrowser_SRCS
|
||||
../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp
|
||||
../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp
|
||||
|
||||
|
||||
../ThirdPartyLibs/urdf/urdfdom/urdf_parser/src/pose.cpp
|
||||
../ThirdPartyLibs/urdf/urdfdom/urdf_parser/src/model.cpp
|
||||
../ThirdPartyLibs/urdf/urdfdom/urdf_parser/src/link.cpp
|
||||
../ThirdPartyLibs/urdf/urdfdom/urdf_parser/src/joint.cpp
|
||||
../ThirdPartyLibs/urdf/urdfdom/urdf_parser/include/urdf_parser/urdf_parser.h
|
||||
../ThirdPartyLibs/urdf/urdfdom_headers/urdf_exception/include/urdf_exception/exception.h
|
||||
../ThirdPartyLibs/urdf/urdfdom_headers/urdf_model/include/urdf_model/pose.h
|
||||
../ThirdPartyLibs/urdf/urdfdom_headers/urdf_model/include/urdf_model/model.h
|
||||
../ThirdPartyLibs/urdf/urdfdom_headers/urdf_model/include/urdf_model/link.h
|
||||
../ThirdPartyLibs/urdf/urdfdom_headers/urdf_model/include/urdf_model/joint.h
|
||||
../ThirdPartyLibs/tinyxml/tinystr.cpp
|
||||
../ThirdPartyLibs/tinyxml/tinyxml.cpp
|
||||
../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp
|
||||
../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp
|
||||
../ThirdPartyLibs/urdf/boost_replacement/lexical_cast.h
|
||||
../ThirdPartyLibs/urdf/boost_replacement/shared_ptr.h
|
||||
../ThirdPartyLibs/urdf/boost_replacement/printf_console.cpp
|
||||
../ThirdPartyLibs/urdf/boost_replacement/printf_console.h
|
||||
../ThirdPartyLibs/urdf/boost_replacement/string_split.cpp
|
||||
../ThirdPartyLibs/urdf/boost_replacement/string_split.h
|
||||
../Utils/b3Clock.cpp
|
||||
../Utils/b3Clock.h
|
||||
../Utils/b3ResourcePath.cpp
|
||||
../Utils/b3ResourcePath.h
|
||||
${ExampleBrowser_SRCS}
|
||||
${ExampleBrowser_HDRS}
|
||||
${GwenGUISupport_SRCS}
|
||||
${GwenGUISupport_HDRS}
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/build3/bullet.rc
|
||||
)
|
||||
|
||||
IF (WIN32)
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/Glew
|
||||
)
|
||||
ADD_DEFINITIONS(-DGLEW_STATIC)
|
||||
ELSE(WIN32)
|
||||
IF(APPLE)
|
||||
find_library(COCOA NAMES Cocoa)
|
||||
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 )
|
||||
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(
|
||||
.
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs
|
||||
)
|
||||
|
||||
|
||||
LINK_LIBRARIES(
|
||||
Bullet3Common BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen
|
||||
BulletExampleBrowserLib Bullet3Common BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen
|
||||
)
|
||||
|
||||
IF (WIN32)
|
||||
SET(App_ExampleBrowser_SRCS ${App_ExampleBrowser_SRCS} )
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/Glew
|
||||
)
|
||||
@@ -229,7 +268,9 @@ ENDIF(WIN32)
|
||||
|
||||
|
||||
ADD_EXECUTABLE(App_ExampleBrowser
|
||||
${App_ExampleBrowser_SRCS}
|
||||
main.cpp
|
||||
ExampleEntries.cpp
|
||||
ExampleEntries.h
|
||||
)
|
||||
|
||||
|
||||
|
||||
@@ -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);
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -13,7 +13,7 @@
|
||||
#include "../Utils/b3Clock.h"
|
||||
|
||||
#include "ExampleEntries.h"
|
||||
#include "Bullet3Common/b3Logging.h"
|
||||
#include "Bullet3Common/b3Scalar.h"
|
||||
#include "../SharedMemory/InProcessMemory.h"
|
||||
|
||||
void ExampleBrowserThreadFunc(void* userPtr,void* lsMemory);
|
||||
@@ -22,9 +22,19 @@ void* ExampleBrowserMemoryFunc();
|
||||
#include <stdio.h>
|
||||
//#include "BulletMultiThreaded/PlatformDefinitions.h"
|
||||
|
||||
#include "Bullet3Common/b3Logging.h"
|
||||
#include "ExampleEntries.h"
|
||||
#include "LinearMath/btAlignedObjectArray.h"
|
||||
#include "EmptyExample.h"
|
||||
|
||||
#include "../SharedMemory/PhysicsServerExample.h"
|
||||
#include "../SharedMemory/PhysicsClientExample.h"
|
||||
|
||||
#ifndef _WIN32
|
||||
#include "../MultiThreading/b3PosixThreadSupport.h"
|
||||
|
||||
|
||||
|
||||
static b3ThreadSupportInterface* createExampleBrowserThreadSupport(int numThreads)
|
||||
{
|
||||
b3PosixThreadSupport::ThreadConstructionInfo constructionInfo("testThreads",
|
||||
@@ -38,6 +48,7 @@ static b3ThreadSupportInterface* createExampleBrowserThreadSupport(int numThread
|
||||
}
|
||||
|
||||
|
||||
|
||||
#elif defined( _WIN32)
|
||||
#include "../MultiThreading/b3Win32ThreadSupport.h"
|
||||
|
||||
@@ -52,6 +63,138 @@ b3ThreadSupportInterface* createExampleBrowserThreadSupport(int numThreads)
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
struct ExampleBrowserArgs
|
||||
{
|
||||
ExampleBrowserArgs()
|
||||
@@ -91,7 +234,7 @@ void ExampleBrowserThreadFunc(void* userPtr,void* lsMemory)
|
||||
b3Clock clock;
|
||||
|
||||
|
||||
ExampleEntries examples;
|
||||
ExampleEntriesPhysicsServer examples;
|
||||
examples.initExampleEntries();
|
||||
|
||||
DefaultBrowser* exampleBrowser = new DefaultBrowser(&examples);
|
||||
@@ -147,6 +290,7 @@ struct btInProcessExampleBrowserInternalData
|
||||
};
|
||||
|
||||
|
||||
|
||||
btInProcessExampleBrowserInternalData* btCreateInProcessExampleBrowser(int argc,char** argv2)
|
||||
{
|
||||
|
||||
@@ -231,7 +375,7 @@ void btShutDownExampleBrowser(btInProcessExampleBrowserInternalData* data)
|
||||
|
||||
struct btInProcessExampleBrowserMainThreadInternalData
|
||||
{
|
||||
ExampleEntries m_examples;
|
||||
ExampleEntriesPhysicsServer m_examples;
|
||||
DefaultBrowser* m_exampleBrowser;
|
||||
SharedMemoryInterface* m_sharedMem;
|
||||
b3Clock m_clock;
|
||||
|
||||
@@ -723,6 +723,8 @@ bool OpenGLExampleBrowser::init(int argc, char* argv[])
|
||||
char title[1024];
|
||||
sprintf(title,"%s using OpenGL3+. %s", appTitle,optMode);
|
||||
simpleApp = new SimpleOpenGL3App(title,width,height, gAllowRetina);
|
||||
|
||||
|
||||
s_app = simpleApp;
|
||||
}
|
||||
#endif
|
||||
@@ -735,6 +737,10 @@ bool OpenGLExampleBrowser::init(int argc, char* argv[])
|
||||
|
||||
s_instancingRenderer = s_app->m_renderer;
|
||||
s_window = s_app->m_window;
|
||||
|
||||
width = s_window->getWidth();
|
||||
height = s_window->getHeight();
|
||||
|
||||
prevMouseMoveCallback = s_window->getMouseMoveCallback();
|
||||
s_window->setMouseMoveCallback(MyMouseMoveCallback);
|
||||
|
||||
@@ -818,8 +824,6 @@ bool OpenGLExampleBrowser::init(int argc, char* argv[])
|
||||
///add some demos to the gAllExamples
|
||||
|
||||
|
||||
|
||||
|
||||
int numDemos = gAllExamples->getNumRegisteredExamples();
|
||||
|
||||
//char nodeText[1024];
|
||||
|
||||
@@ -22,7 +22,7 @@ int main(int argc, char* argv[])
|
||||
b3Clock clock;
|
||||
|
||||
|
||||
ExampleEntries examples;
|
||||
ExampleEntriesAll examples;
|
||||
examples.initExampleEntries();
|
||||
|
||||
ExampleBrowserInterface* exampleBrowser = new DefaultBrowser(&examples);
|
||||
|
||||
@@ -59,7 +59,7 @@ if (BUILD_SHARED_LIBS)
|
||||
else()
|
||||
set (CMAKE_THREAD_PREFER_PTHREAD TRUE)
|
||||
FIND_PACKAGE(Threads)
|
||||
target_link_libraries(OpenGLWindow ${CMAKE_THREAD_LIBS_INIT})
|
||||
target_link_libraries(OpenGLWindow dl ${CMAKE_THREAD_LIBS_INIT})
|
||||
endif()
|
||||
endif()
|
||||
|
||||
|
||||
@@ -101,6 +101,9 @@ public:
|
||||
virtual float getTimeInSeconds();
|
||||
|
||||
|
||||
virtual int getWidth() const;
|
||||
virtual int getHeight() const;
|
||||
|
||||
|
||||
virtual void setRenderCallback( b3RenderCallback renderCallback);
|
||||
|
||||
|
||||
@@ -423,8 +423,8 @@ void MacOpenGLWindow::createWindow(const b3gWindowConstructionInfo& ci)
|
||||
[m_internalData->m_window makeKeyAndOrderFront: nil];
|
||||
|
||||
[m_internalData->m_myview MakeCurrent];
|
||||
//m_internalData->m_width = m_internalData->m_myview.GetWindowWidth;
|
||||
//m_internalData->m_height = m_internalData->m_myview.GetWindowHeight;
|
||||
m_internalData->m_width = m_internalData->m_myview.GetWindowWidth;
|
||||
m_internalData->m_height = m_internalData->m_myview.GetWindowHeight;
|
||||
|
||||
|
||||
[NSApp activateIgnoringOtherApps:YES];
|
||||
@@ -1132,6 +1132,21 @@ void MacOpenGLWindow::getMouseCoordinates(int& x, int& y)
|
||||
|
||||
}
|
||||
|
||||
int MacOpenGLWindow::getWidth() const
|
||||
{
|
||||
if (m_internalData && m_internalData->m_myview && m_internalData->m_myview.GetWindowWidth)
|
||||
return m_internalData->m_myview.GetWindowWidth;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int MacOpenGLWindow::getHeight() const
|
||||
{
|
||||
if (m_internalData && m_internalData->m_myview && m_internalData->m_myview.GetWindowHeight)
|
||||
return m_internalData->m_myview.GetWindowHeight;
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
void MacOpenGLWindow::setResizeCallback(b3ResizeCallback resizeCallback)
|
||||
{
|
||||
[m_internalData->m_myview setResizeCallback:resizeCallback];
|
||||
|
||||
@@ -56,7 +56,10 @@ static void SimpleResizeCallback( float widthf, float heightf)
|
||||
{
|
||||
int width = (int)widthf;
|
||||
int height = (int)heightf;
|
||||
if (gApp && gApp->m_instancingRenderer)
|
||||
gApp->m_instancingRenderer->resize(width,height);
|
||||
|
||||
if (gApp && gApp->m_primRenderer)
|
||||
gApp->m_primRenderer->setScreenSize(width,height);
|
||||
|
||||
}
|
||||
@@ -115,6 +118,7 @@ extern unsigned char OpenSansData[];
|
||||
SimpleOpenGL3App::SimpleOpenGL3App( const char* title, int width,int height, bool allowRetina)
|
||||
{
|
||||
gApp = this;
|
||||
|
||||
m_data = new SimpleInternalData;
|
||||
m_data->m_frameDumpPngFileName = 0;
|
||||
m_data->m_renderTexture = 0;
|
||||
@@ -123,6 +127,7 @@ SimpleOpenGL3App::SimpleOpenGL3App( const char* title, int width,int height, boo
|
||||
m_data->m_upAxis = 1;
|
||||
|
||||
m_window = new b3gDefaultOpenGLWindow();
|
||||
|
||||
m_window->setAllowRetina(allowRetina);
|
||||
|
||||
b3gWindowConstructionInfo ci;
|
||||
@@ -141,6 +146,9 @@ SimpleOpenGL3App::SimpleOpenGL3App( const char* title, int width,int height, boo
|
||||
1.f);
|
||||
|
||||
m_window->startRendering();
|
||||
width = m_window->getWidth();
|
||||
height = m_window->getHeight();
|
||||
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
|
||||
#ifndef __APPLE__
|
||||
@@ -160,16 +168,20 @@ SimpleOpenGL3App::SimpleOpenGL3App( const char* title, int width,int height, boo
|
||||
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
|
||||
m_primRenderer = new GLPrimitiveRenderer(width,height);
|
||||
m_parameterInterface = 0;
|
||||
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
|
||||
m_instancingRenderer = new GLInstancingRenderer(128*1024,64*1024*1024);
|
||||
m_primRenderer = new GLPrimitiveRenderer(width,height);
|
||||
|
||||
m_renderer = m_instancingRenderer ;
|
||||
m_window->setResizeCallback(SimpleResizeCallback);
|
||||
|
||||
|
||||
m_instancingRenderer->init();
|
||||
m_instancingRenderer->resize(width,height);
|
||||
|
||||
m_primRenderer->setScreenSize(width,height);
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
|
||||
m_instancingRenderer->InitShaders();
|
||||
@@ -178,7 +190,6 @@ SimpleOpenGL3App::SimpleOpenGL3App( const char* title, int width,int height, boo
|
||||
m_window->setMouseButtonCallback(SimpleMouseButtonCallback);
|
||||
m_window->setKeyboardCallback(SimpleKeyboardCallback);
|
||||
m_window->setWheelCallback(SimpleWheelCallback);
|
||||
m_window->setResizeCallback(SimpleResizeCallback);
|
||||
|
||||
TwGenerateDefaultFonts();
|
||||
m_data->m_fontTextureId = BindFont(g_DefaultNormalFont);
|
||||
|
||||
@@ -180,6 +180,21 @@ int Win32OpenGLWindow::fileOpenDialog(char* fileName, int maxFileNameLength)
|
||||
//return 0;
|
||||
}
|
||||
|
||||
int Win32OpenGLWindow::getWidth() const
|
||||
{
|
||||
if (m_data)
|
||||
return m_data->m_openglViewportWidth;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int Win32OpenGLWindow::getHeight() const
|
||||
{
|
||||
if (m_data)
|
||||
return m_data->m_openglViewportHeight;
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
@@ -53,6 +53,9 @@ public:
|
||||
virtual float getRetinaScale() const {return 1.f;}
|
||||
virtual void setAllowRetina(bool /*allowRetina*/) {};
|
||||
|
||||
virtual int getWidth() const;
|
||||
virtual int getHeight() const;
|
||||
|
||||
virtual int fileOpenDialog(char* fileName, int maxFileNameLength);
|
||||
};
|
||||
|
||||
|
||||
@@ -1076,6 +1076,20 @@ b3KeyboardCallback X11OpenGLWindow::getKeyboardCallback()
|
||||
return m_data->m_keyboardCallback;
|
||||
}
|
||||
|
||||
int X11OpenGLWindow::getWidth() const
|
||||
{
|
||||
if (m_data)
|
||||
return m_data->m_glWidth;
|
||||
return 0;
|
||||
}
|
||||
int X11OpenGLWindow::getHeight() const
|
||||
{
|
||||
if (m_data)
|
||||
return m_data->m_glHeight;
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
int X11OpenGLWindow::fileOpenDialog(char* filename, int maxNameLength)
|
||||
|
||||
@@ -65,9 +65,14 @@ public:
|
||||
|
||||
virtual void setWindowTitle(const char* title);
|
||||
|
||||
virtual int getWidth() const;
|
||||
|
||||
virtual int getHeight() const;
|
||||
|
||||
int fileOpenDialog(char* filename, int maxNameLength);
|
||||
};
|
||||
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
24
examples/pybullet/CMakeLists.txt
Normal file
24
examples/pybullet/CMakeLists.txt
Normal file
@@ -0,0 +1,24 @@
|
||||
IF (BUILD_SHARED_LIBS)
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs
|
||||
/usr/include/python2.7
|
||||
)
|
||||
|
||||
SET(pybullet_SRCS
|
||||
pybullet.c
|
||||
../../examples/ExampleBrowser/ExampleEntries.cpp
|
||||
)
|
||||
|
||||
|
||||
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 Python)
|
||||
ENDIF (BUILD_SHARED_LIBS)
|
||||
|
||||
|
||||
@@ -20,6 +20,7 @@ project ("pybullet")
|
||||
".",
|
||||
"../../src",
|
||||
"../ThirdPartyLibs",
|
||||
"/usr/include/python2.7",
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -8,11 +8,17 @@
|
||||
#endif
|
||||
|
||||
static PyObject *SpamError;
|
||||
static b3PhysicsClientHandle sm;
|
||||
static b3PhysicsClientHandle sm=0;
|
||||
|
||||
|
||||
static PyObject *
|
||||
spam_step(PyObject *self, PyObject *args)
|
||||
pybullet_stepSimulation(PyObject *self, PyObject *args)
|
||||
{
|
||||
if (0==sm)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
{
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
@@ -29,8 +35,46 @@ return PyLong_FromLong(1);
|
||||
}
|
||||
|
||||
static PyObject *
|
||||
spam_loadURDF(PyObject* self, PyObject* args)
|
||||
pybullet_connectPhysicsServer(PyObject *self, PyObject *args)
|
||||
{
|
||||
if (0!=sm)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Already connected to physics server, disconnect first.");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
{
|
||||
sm = b3ConnectSharedMemory(SHARED_MEMORY_KEY);
|
||||
}
|
||||
|
||||
return PyLong_FromLong(1);
|
||||
}
|
||||
|
||||
static PyObject *
|
||||
pybullet_disconnectPhysicsServer(PyObject *self, PyObject *args)
|
||||
{
|
||||
if (0==sm)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||
return NULL;
|
||||
}
|
||||
{
|
||||
b3DisconnectSharedMemory(sm);
|
||||
sm = 0;
|
||||
}
|
||||
|
||||
return PyLong_FromLong(1);
|
||||
}
|
||||
|
||||
|
||||
static PyObject *
|
||||
pybullet_loadURDF(PyObject* self, PyObject* args)
|
||||
{
|
||||
if (0==sm)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||
return NULL;
|
||||
}
|
||||
int size= PySequence_Size(args);
|
||||
|
||||
int bodyIndex = -1;
|
||||
@@ -61,13 +105,14 @@ spam_loadURDF(PyObject* self, PyObject* args)
|
||||
&startOrnX,&startOrnY,&startOrnZ, &startOwnW))
|
||||
return NULL;
|
||||
}
|
||||
{
|
||||
printf("urdf filename = %s\n", urdfFileName);
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(sm, urdfFileName);
|
||||
|
||||
//setting the initial position, orientation and other arguments are optional
|
||||
int ret = b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ);
|
||||
b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ);
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
if (statusType!=CMD_URDF_LOADING_COMPLETED)
|
||||
@@ -76,14 +121,42 @@ spam_loadURDF(PyObject* self, PyObject* args)
|
||||
return NULL;
|
||||
}
|
||||
bodyIndex = b3GetStatusBodyIndex(statusHandle);
|
||||
}
|
||||
return PyLong_FromLong(bodyIndex);
|
||||
}
|
||||
static PyObject *
|
||||
pybullet_resetSimulation(PyObject* self, PyObject* args)
|
||||
{
|
||||
if (0==sm)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
{
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, b3InitResetSimulationCommand(sm));
|
||||
// ASSERT_EQ(b3GetStatusType(statusHandle), CMD_RESET_SIMULATION_COMPLETED);
|
||||
}
|
||||
return PyLong_FromLong(1);
|
||||
|
||||
}
|
||||
|
||||
static PyMethodDef SpamMethods[] = {
|
||||
{"step", spam_step, METH_VARARGS,
|
||||
"Step the simulation forward."},
|
||||
{"loadURDF", spam_loadURDF, METH_VARARGS,
|
||||
{"loadURDF", pybullet_loadURDF, METH_VARARGS,
|
||||
"Create a multibody by loading a URDF file."},
|
||||
|
||||
{"connect", pybullet_connectPhysicsServer, METH_VARARGS,
|
||||
"Connect to an existing physics server (using shared memory by default)."},
|
||||
{"disconnect", pybullet_disconnectPhysicsServer, METH_VARARGS,
|
||||
"Disconnect from the physics server."},
|
||||
|
||||
{"resetSimulation", pybullet_resetSimulation, METH_VARARGS,
|
||||
"Reset the simulation: remove all objects and start from an empty world."},
|
||||
|
||||
{"stepSimulation", pybullet_stepSimulation, METH_VARARGS,
|
||||
"Step the simulation using forward dynamics."},
|
||||
|
||||
{NULL, NULL, 0, NULL} /* Sentinel */
|
||||
};
|
||||
|
||||
@@ -92,16 +165,7 @@ PyMODINIT_FUNC
|
||||
initpybullet(void)
|
||||
{
|
||||
|
||||
b3PhysicsClientHandle h;
|
||||
|
||||
PyObject *m;
|
||||
sm = b3ConnectSharedMemory(SHARED_MEMORY_KEY);
|
||||
|
||||
//#ifdef __APPLE__
|
||||
//sm = b3CreateInProcessPhysicsServerAndConnectMainThread(0,0);
|
||||
//#else
|
||||
//sm = b3CreateInProcessPhysicsServerAndConnect(0,0);
|
||||
//#endif
|
||||
m = Py_InitModule("pybullet", SpamMethods);
|
||||
if (m == NULL)
|
||||
return;
|
||||
|
||||
Reference in New Issue
Block a user