Merge remote-tracking branch 'bp/master'

This commit is contained in:
erwincoumans 2019-06-01 07:29:31 -07:00
commit 36896db828
5 changed files with 249 additions and 178 deletions

View File

@ -291,8 +291,6 @@ IF (OPENGL_FOUND)
MESSAGE(${OPENGL_LIBRARIES})
ELSE (OPENGL_FOUND)
MESSAGE("OPENGL NOT FOUND")
SET(OPENGL_gl_LIBRARY opengl32)
SET(OPENGL_glu_LIBRARY glu32)
ENDIF (OPENGL_FOUND)
@ -472,6 +470,7 @@ list (APPEND BULLET_LIBRARIES BulletInverseDynamics)
list (APPEND BULLET_LIBRARIES BulletCollision)
list (APPEND BULLET_LIBRARIES BulletDynamics)
list (APPEND BULLET_LIBRARIES BulletSoftBody)
list (APPEND BULLET_LIBRARIES bullet_c_api)
set (BULLET_USE_FILE ${BULLET_CONFIG_CMAKE_PATH}/UseBullet.cmake)
configure_file ( ${CMAKE_CURRENT_SOURCE_DIR}/BulletConfig.cmake.in
${CMAKE_CURRENT_BINARY_DIR}/BulletConfig.cmake

View File

@ -1,6 +1,6 @@
SUBDIRS( HelloWorld BasicDemo )
IF(BUILD_BULLET3)
SUBDIRS( ExampleBrowser RobotSimulator SharedMemory ThirdPartyLibs/Gwen ThirdPartyLibs/BussIK ThirdPartyLibs/clsocket OpenGLWindow TwoJoint )
SUBDIRS( ExampleBrowser RobotSimulator SharedMemory ThirdPartyLibs/Gwen ThirdPartyLibs/BussIK ThirdPartyLibs/clsocket OpenGLWindow TwoJoint c_api)
ENDIF()
IF(BUILD_PYBULLET)

View File

@ -0,0 +1,210 @@
INCLUDE_DIRECTORIES(
${BULLET_PHYSICS_SOURCE_DIR}/src
${BULLET_PHYSICS_SOURCE_DIR}/examples
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/enet/include
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/clsocket/src
)
SET(
bullet_c_api_SRCS
../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.h
../../examples/SharedMemory/plugins/stablePDPlugin/Shape.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/Shape.h
../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.h
../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.h
../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.h
../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.h
../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.h
../../examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h
../../examples/SharedMemory/IKTrajectoryHelper.cpp
../../examples/SharedMemory/IKTrajectoryHelper.h
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.h
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.h
../../examples/OpenGLWindow/SimpleCamera.cpp
../../examples/OpenGLWindow/SimpleCamera.h
../../examples/TinyRenderer/geometry.cpp
../../examples/TinyRenderer/model.cpp
../../examples/TinyRenderer/tgaimage.cpp
../../examples/TinyRenderer/our_gl.cpp
../../examples/TinyRenderer/TinyRenderer.cpp
../../examples/SharedMemory/InProcessMemory.cpp
../../examples/SharedMemory/PhysicsClient.cpp
../../examples/SharedMemory/PhysicsClient.h
../../examples/SharedMemory/PhysicsServer.cpp
../../examples/SharedMemory/PhysicsServer.h
../../examples/SharedMemory/PhysicsServerExample.cpp
../../examples/SharedMemory/PhysicsServerExampleBullet2.cpp
../../examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.h
../../examples/SharedMemory/PhysicsDirect.cpp
../../examples/SharedMemory/PhysicsDirect.h
../../examples/SharedMemory/PhysicsDirectC_API.cpp
../../examples/SharedMemory/PhysicsDirectC_API.h
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
../../examples/SharedMemory/b3PluginManager.cpp
../../examples/SharedMemory/b3PluginManager.h
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.h
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.h
../../examples/SharedMemory/PhysicsClientC_API.cpp
../../examples/SharedMemory/PhysicsClientC_API.h
../../examples/SharedMemory/Win32SharedMemory.cpp
../../examples/SharedMemory/Win32SharedMemory.h
../../examples/SharedMemory/PosixSharedMemory.cpp
../../examples/SharedMemory/PosixSharedMemory.h
../../examples/Utils/b3ResourcePath.cpp
../../examples/Utils/b3ResourcePath.h
../../examples/Utils/RobotLoggingUtil.cpp
../../examples/Utils/RobotLoggingUtil.h
../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h
../../examples/ThirdPartyLibs/stb_image/stb_image.cpp
../../examples/ThirdPartyLibs/stb_image/stb_image_write.cpp
../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp
../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp
../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp
../../examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp
../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp
../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp
../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp
../../examples/Importers/ImportURDFDemo/UrdfParser.cpp
../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp
../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp
../../examples/MultiThreading/b3PosixThreadSupport.cpp
../../examples/MultiThreading/b3Win32ThreadSupport.cpp
../../examples/MultiThreading/b3ThreadSupportInterface.cpp
)
IF(BUILD_PYBULLET_CLSOCKET)
ADD_DEFINITIONS(-DBT_ENABLE_CLSOCKET)
ENDIF(BUILD_PYBULLET_CLSOCKET)
IF(WIN32)
IF(BUILD_PYBULLET_ENET)
ADD_DEFINITIONS(-DWIN32 -DBT_ENABLE_ENET)
ENDIF(BUILD_PYBULLET_ENET)
IF(BUILD_PYBULLET_CLSOCKET)
ADD_DEFINITIONS(-DWIN32)
ENDIF(BUILD_PYBULLET_CLSOCKET)
ELSE(WIN32)
IF(BUILD_PYBULLET_ENET)
ADD_DEFINITIONS(-DHAS_SOCKLEN_T -DBT_ENABLE_ENET)
ENDIF(BUILD_PYBULLET_ENET)
IF(BUILD_PYBULLET_CLSOCKET)
ADD_DEFINITIONS(${OSDEF})
ENDIF(BUILD_PYBULLET_CLSOCKET)
ENDIF(WIN32)
IF(BUILD_PYBULLET_ENET)
SET(
bullet_c_api_SRCS
${bullet_c_api_SRCS}
../../examples/SharedMemory/PhysicsClientUDP.cpp
../../examples/SharedMemory/PhysicsClientUDP_C_API.cpp
../../examples/SharedMemory/PhysicsClientUDP.h
../../examples/SharedMemory/PhysicsClientUDP_C_API.h
../../examples/ThirdPartyLibs/enet/win32.c
../../examples/ThirdPartyLibs/enet/unix.c
../../examples/ThirdPartyLibs/enet/callbacks.c
../../examples/ThirdPartyLibs/enet/compress.c
../../examples/ThirdPartyLibs/enet/host.c
../../examples/ThirdPartyLibs/enet/list.c
../../examples/ThirdPartyLibs/enet/packet.c
../../examples/ThirdPartyLibs/enet/peer.c
../../examples/ThirdPartyLibs/enet/protocol.c
)
ENDIF(BUILD_PYBULLET_ENET)
IF(BUILD_PYBULLET_CLSOCKET)
SET(
bullet_c_api_SRCS
${bullet_c_api_SRCS}
../../examples/SharedMemory/PhysicsClientTCP.cpp
../../examples/SharedMemory/PhysicsClientTCP.h
../../examples/SharedMemory/PhysicsClientTCP_C_API.cpp
../../examples/SharedMemory/PhysicsClientTCP_C_API.h
../../examples/ThirdPartyLibs/clsocket/src/SimpleSocket.cpp
../../examples/ThirdPartyLibs/clsocket/src/ActiveSocket.cpp
../../examples/ThirdPartyLibs/clsocket/src/PassiveSocket.cpp
)
ENDIF()
ADD_LIBRARY(bullet_c_api SHARED ${bullet_c_api_SRCS})
SET_TARGET_PROPERTIES(bullet_c_api PROPERTIES PREFIX "")
SET_TARGET_PROPERTIES(bullet_c_api PROPERTIES POSTFIX "")
SET_TARGET_PROPERTIES(bullet_c_api PROPERTIES VERSION ${BULLET_VERSION})
SET_TARGET_PROPERTIES(bullet_c_api PROPERTIES SOVERSION ${BULLET_VERSION})
SET_TARGET_PROPERTIES(bullet_c_api PROPERTIES DEBUG_POSTFIX "_d")
IF(WIN32)
IF(BUILD_PYBULLET_ENET OR BUILD_PYBULLET_CLSOCKET)
TARGET_LINK_LIBRARIES(bullet_c_api ws2_32)
ENDIF(BUILD_PYBULLET_ENET OR BUILD_PYBULLET_CLSOCKET)
ENDIF(WIN32)
TARGET_LINK_LIBRARIES(
bullet_c_api
BulletExampleBrowserLib
BulletFileLoader
BulletWorldImporter
BulletSoftBody
BulletDynamics
BulletCollision
BulletInverseDynamicsUtils
BulletInverseDynamics
LinearMath
OpenGLWindow
gwen
BussIK
Bullet3Common
)
TARGET_LINK_LIBRARIES(bullet_c_api ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY})
IF (INSTALL_LIBS)
IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES)
#INSTALL of other files requires CMake 2.6
IF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5)
IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
INSTALL(TARGETS bullet_c_api DESTINATION lib)
ELSE (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
INSTALL(TARGETS bullet_c_api RUNTIME DESTINATION bin
LIBRARY DESTINATION lib${LIB_SUFFIX}
ARCHIVE DESTINATION lib${LIB_SUFFIX})
ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
ENDIF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5)
IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
SET_TARGET_PROPERTIES(bullet_c_api PROPERTIES FRAMEWORK true)
SET_TARGET_PROPERTIES(bullet_c_api PROPERTIES PUBLIC_HEADER "${Root_HDRS}")
# Have to list out sub-directories manually:
ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES)
ENDIF (INSTALL_LIBS)

View File

@ -1,165 +1,21 @@
INCLUDE_DIRECTORIES(
${BULLET_PHYSICS_SOURCE_DIR}/src
${BULLET_PHYSICS_SOURCE_DIR}/examples
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/enet/include
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/clsocket/src
${PYTHON_INCLUDE_DIRS}
)
INCLUDE_DIRECTORIES(
${BULLET_PHYSICS_SOURCE_DIR}/src
${BULLET_PHYSICS_SOURCE_DIR}/examples
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/enet/include
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/clsocket/src
${PYTHON_INCLUDE_DIRS}
)
IF(BUILD_PYBULLET_NUMPY)
INCLUDE_DIRECTORIES(
${PYTHON_NUMPY_INCLUDE_DIR}
)
INCLUDE_DIRECTORIES(${PYTHON_NUMPY_INCLUDE_DIR})
ENDIF()
ADD_DEFINITIONS(-DSTATIC_LINK_SPD_PLUGIN)
SET(pybullet_SRCS
pybullet.c
../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.h
../../examples/SharedMemory/plugins/stablePDPlugin/Shape.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/Shape.h
../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.h
../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.h
../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.h
../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.h
../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.h
../../examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h
../../examples/SharedMemory/IKTrajectoryHelper.cpp
../../examples/SharedMemory/IKTrajectoryHelper.h
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.h
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.h
../../examples/OpenGLWindow/SimpleCamera.cpp
../../examples/OpenGLWindow/SimpleCamera.h
../../examples/TinyRenderer/geometry.cpp
../../examples/TinyRenderer/model.cpp
../../examples/TinyRenderer/tgaimage.cpp
../../examples/TinyRenderer/our_gl.cpp
../../examples/TinyRenderer/TinyRenderer.cpp
../../examples/SharedMemory/InProcessMemory.cpp
../../examples/SharedMemory/PhysicsClient.cpp
../../examples/SharedMemory/PhysicsClient.h
../../examples/SharedMemory/PhysicsServer.cpp
../../examples/SharedMemory/PhysicsServer.h
../../examples/SharedMemory/PhysicsServerExample.cpp
../../examples/SharedMemory/PhysicsServerExampleBullet2.cpp
../../examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.h
../../examples/SharedMemory/PhysicsDirect.cpp
../../examples/SharedMemory/PhysicsDirect.h
../../examples/SharedMemory/PhysicsDirectC_API.cpp
../../examples/SharedMemory/PhysicsDirectC_API.h
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
../../examples/SharedMemory/b3PluginManager.cpp
../../examples/SharedMemory/b3PluginManager.h
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.h
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.h
../../examples/SharedMemory/PhysicsClientC_API.cpp
../../examples/SharedMemory/PhysicsClientC_API.h
../../examples/SharedMemory/Win32SharedMemory.cpp
../../examples/SharedMemory/Win32SharedMemory.h
../../examples/SharedMemory/PosixSharedMemory.cpp
../../examples/SharedMemory/PosixSharedMemory.h
../../examples/Utils/b3ResourcePath.cpp
../../examples/Utils/b3ResourcePath.h
../../examples/Utils/RobotLoggingUtil.cpp
../../examples/Utils/RobotLoggingUtil.h
../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h
../../examples/ThirdPartyLibs/stb_image/stb_image.cpp
../../examples/ThirdPartyLibs/stb_image/stb_image_write.cpp
../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp
../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp
../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp
../../examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp
../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp
../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp
../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp
../../examples/Importers/ImportURDFDemo/UrdfParser.cpp
../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp
../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp
../../examples/MultiThreading/b3PosixThreadSupport.cpp
../../examples/MultiThreading/b3Win32ThreadSupport.cpp
../../examples/MultiThreading/b3ThreadSupportInterface.cpp
SET(
pybullet_SRCS
pybullet.c
)
IF(BUILD_PYBULLET_CLSOCKET)
ADD_DEFINITIONS(-DBT_ENABLE_CLSOCKET)
ENDIF(BUILD_PYBULLET_CLSOCKET)
IF(WIN32)
LINK_LIBRARIES(
${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY}
)
IF(BUILD_PYBULLET_ENET)
ADD_DEFINITIONS(-DWIN32 -DBT_ENABLE_ENET)
ENDIF(BUILD_PYBULLET_ENET)
IF(BUILD_PYBULLET_CLSOCKET)
ADD_DEFINITIONS(-DWIN32)
ENDIF(BUILD_PYBULLET_CLSOCKET)
ELSE(WIN32)
IF(BUILD_PYBULLET_ENET)
ADD_DEFINITIONS(-DHAS_SOCKLEN_T -DBT_ENABLE_ENET)
ENDIF(BUILD_PYBULLET_ENET)
IF(BUILD_PYBULLET_CLSOCKET)
ADD_DEFINITIONS(${OSDEF})
ENDIF(BUILD_PYBULLET_CLSOCKET)
ENDIF(WIN32)
IF(BUILD_PYBULLET_ENET)
set(pybullet_SRCS ${pybullet_SRCS}
../../examples/SharedMemory/PhysicsClientUDP.cpp
../../examples/SharedMemory/PhysicsClientUDP_C_API.cpp
../../examples/SharedMemory/PhysicsClientUDP.h
../../examples/SharedMemory/PhysicsClientUDP_C_API.h
../../examples/ThirdPartyLibs/enet/win32.c
../../examples/ThirdPartyLibs/enet/unix.c
../../examples/ThirdPartyLibs/enet/callbacks.c
../../examples/ThirdPartyLibs/enet/compress.c
../../examples/ThirdPartyLibs/enet/host.c
../../examples/ThirdPartyLibs/enet/list.c
../../examples/ThirdPartyLibs/enet/packet.c
../../examples/ThirdPartyLibs/enet/peer.c
../../examples/ThirdPartyLibs/enet/protocol.c
)
ENDIF(BUILD_PYBULLET_ENET)
IF(BUILD_PYBULLET_CLSOCKET)
set(pybullet_SRCS ${pybullet_SRCS}
../../examples/SharedMemory/PhysicsClientTCP.cpp
../../examples/SharedMemory/PhysicsClientTCP.h
../../examples/SharedMemory/PhysicsClientTCP_C_API.cpp
../../examples/SharedMemory/PhysicsClientTCP_C_API.h
../../examples/ThirdPartyLibs/clsocket/src/SimpleSocket.cpp
../../examples/ThirdPartyLibs/clsocket/src/ActiveSocket.cpp
../../examples/ThirdPartyLibs/clsocket/src/PassiveSocket.cpp
)
ENDIF()
ADD_LIBRARY(pybullet SHARED ${pybullet_SRCS})
@ -170,35 +26,41 @@ SET_TARGET_PROPERTIES(pybullet PROPERTIES VERSION ${BULLET_VERSION})
SET_TARGET_PROPERTIES(pybullet PROPERTIES SOVERSION ${BULLET_VERSION})
SET_TARGET_PROPERTIES(pybullet PROPERTIES DEBUG_POSTFIX "_d")
IF(WIN32)
IF(BUILD_PYBULLET_ENET OR BUILD_PYBULLET_CLSOCKET)
TARGET_LINK_LIBRARIES(pybullet ws2_32 )
ENDIF(BUILD_PYBULLET_ENET OR BUILD_PYBULLET_CLSOCKET)
IF(BUILD_PYBULLET_ENET OR BUILD_PYBULLET_CLSOCKET)
TARGET_LINK_LIBRARIES(pybullet ws2_32)
ENDIF(BUILD_PYBULLET_ENET OR BUILD_PYBULLET_CLSOCKET)
SET_TARGET_PROPERTIES(pybullet PROPERTIES SUFFIX ".pyd" )
SET_TARGET_PROPERTIES(pybullet PROPERTIES SUFFIX ".pyd")
ENDIF(WIN32)
IF (APPLE)
SET_TARGET_PROPERTIES(pybullet PROPERTIES SUFFIX ".so" )
IF(APPLE)
SET_TARGET_PROPERTIES(pybullet PROPERTIES SUFFIX ".so")
ENDIF()
TARGET_LINK_LIBRARIES(
pybullet
bullet_c_api
)
TARGET_LINK_LIBRARIES(pybullet BulletExampleBrowserLib BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen BussIK Bullet3Common)
IF (WIN32)
IF(WIN32)
TARGET_LINK_LIBRARIES(pybullet ${PYTHON_LIBRARIES})
ELSEIF (APPLE)
SET_TARGET_PROPERTIES(pybullet PROPERTIES LINK_FLAGS "-undefined dynamic_lookup")
ENDIF ()
ELSEIF(APPLE)
SET_TARGET_PROPERTIES(
pybullet
PROPERTIES LINK_FLAGS "-undefined dynamic_lookup"
)
ENDIF()
# else Linux: dont link
IF(WIN32)
SET(PYTHON_SITE_PACKAGES Lib/site-packages CACHE PATH "Python install path")
ELSE()
SET(PYTHON_SITE_PACKAGES lib/python${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}/site-packages CACHE PATH "Python install path")
SET(
PYTHON_SITE_PACKAGES
lib/python${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}/site-packages
CACHE PATH "Python install path"
)
ENDIF()
INSTALL(TARGETS pybullet DESTINATION ${PYTHON_SITE_PACKAGES})

View File

@ -20,7 +20,7 @@ subject to the following restrictions:
#include "btMLCPSolverInterface.h"
#include "btLemkeAlgorithm.h"
///The btLemkeSolver is based on "Fast Implementation of Lemkes Algorithm for Rigid Body Contact Simulation (John E. Lloyd) "
///The btLemkeSolver is based on "Fast Implementation of Lemkes Algorithm for Rigid Body Contact Simulation (John E. Lloyd) "
///It is a slower but more accurate solver. Increase the m_maxLoops for better convergence, at the cost of more CPU time.
///The original implementation of the btLemkeAlgorithm was done by Kilian Grundl from the MBSim team
class btLemkeSolver : public btMLCPSolverInterface
@ -67,7 +67,7 @@ public:
btMatrixXu A1;
btMatrixXu B(n, n);
{
BT_PROFILE("inverse(slow)");
//BT_PROFILE("inverse(slow)");
A1.resize(A.rows(), A.cols());
for (int row = 0; row < A.rows(); row++)
{
@ -174,7 +174,7 @@ public:
y1.resize(n, 1);
btLemkeAlgorithm lemke(M, qq, m_debugLevel);
{
BT_PROFILE("lemke.solve");
//BT_PROFILE("lemke.solve");
lemke.setSystem(M, qq);
z1 = lemke.solve(m_maxLoops);
}