work-in-progress

add UDP network connection for physics client <-> server.
also set spinning friction in rolling friction demo (otherwise objects may keep on spinning forever)
This commit is contained in:
erwincoumans
2016-11-04 13:15:10 -07:00
parent c2ca88bf44
commit 9708392322
52 changed files with 2104 additions and 214 deletions

View File

@@ -3,6 +3,7 @@ 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
${PYTHON_INCLUDE_DIRS}
)
IF(BUILD_PYBULLET_NUMPY)
@@ -16,7 +17,7 @@ SET(pybullet_SRCS
../../examples/SharedMemory/IKTrajectoryHelper.cpp
../../examples/SharedMemory/IKTrajectoryHelper.h
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/TinyRendererVisualShapeConverter.h
../../examples/OpenGLWindow/SimpleCamera.cpp
../../examples/OpenGLWindow/SimpleCamera.h
@@ -42,6 +43,9 @@ SET(pybullet_SRCS
../../examples/SharedMemory/PhysicsServerCommandProcessor.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
@@ -69,20 +73,55 @@ SET(pybullet_SRCS
../../examples/MultiThreading/b3PosixThreadSupport.cpp
../../examples/MultiThreading/b3Win32ThreadSupport.cpp
../../examples/MultiThreading/b3ThreadSupportInterface.cpp
)
IF(WIN32)
LINK_LIBRARIES(
LINK_LIBRARIES(
${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY}
)
IF(BUILD_PYBULLET_ENET)
ADD_DEFINITIONS(-DWIN32 -DBT_ENABLE_ENET)
ENDIF(BUILD_PYBULLET_ENET)
ENDIF(WIN32)
ADD_LIBRARY(pybullet SHARED ${pybullet_SRCS})
IF(BUILD_PYBULLET_ENET)
ADD_LIBRARY(pybullet SHARED ${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
)
ELSE(BUILD_PYBULLET_ENET)
ADD_LIBRARY(pybullet SHARED ${pybullet_SRCS})
ENDIF(BUILD_PYBULLET_ENET)
SET_TARGET_PROPERTIES(pybullet PROPERTIES VERSION ${BULLET_VERSION})
SET_TARGET_PROPERTIES(pybullet PROPERTIES SOVERSION ${BULLET_VERSION})
TARGET_LINK_LIBRARIES(pybullet BulletExampleBrowserLib BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen BussIK Bullet3Common ${PYTHON_LIBRARIES})
SET_TARGET_PROPERTIES(pybullet PROPERTIES DEBUG_POSTFIX "_d")
IF(WIN32)
IF(BUILD_PYBULLET_ENET)
TARGET_LINK_LIBRARIES(pybullet ws2_32 )
ENDIF(BUILD_PYBULLET_ENET)
SET_TARGET_PROPERTIES(pybullet PROPERTIES SUFFIX ".pyd" )
ENDIF(WIN32)
TARGET_LINK_LIBRARIES(pybullet ws2_32 BulletExampleBrowserLib BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen BussIK Bullet3Common ${PYTHON_LIBRARIES})

View File

@@ -33,12 +33,37 @@ project ("pybullet")
}
end
if not _OPTIONS["no-enet"] then
includedirs {"../../examples/ThirdPartyLibs/enet/include"}
if os.is("Windows") then
defines { "WIN32" }
links {"Ws2_32","Winmm"}
end
if os.is("Linux") then
end
if os.is("MacOSX") then
end
links {"enet"}
files {
"../../examples/SharedMemory/PhysicsClientUDP.cpp",
"../../examples/SharedMemory/PhysicsClientUDP.h",
"../../examples/SharedMemory/PhysicsClientUDP_C_API.cpp",
"../../examples/SharedMemory/PhysicsClientUDP_C_API.h",
}
defines {"BT_ENABLE_ENET"}
end
files {
"pybullet.c",
"../../examples/SharedMemory/IKTrajectoryHelper.cpp",
"../../examples/SharedMemory/IKTrajectoryHelper.h",
"../../examples/ExampleBrowser/InProcessExampleBrowser.cpp",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
"../../examples/OpenGLWindow/SimpleCamera.cpp",
"../../examples/OpenGLWindow/SimpleCamera.h",
@@ -64,6 +89,8 @@ project ("pybullet")
"../../examples/SharedMemory/PhysicsServerCommandProcessor.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",

View File

@@ -1,7 +1,9 @@
#include "../SharedMemory/PhysicsClientC_API.h"
#include "../SharedMemory/PhysicsDirectC_API.h"
#include "../SharedMemory/SharedMemoryInProcessPhysicsC_API.h"
#ifdef BT_ENABLE_ENET
#include "../SharedMemory/PhysicsClientUDP_C_API.h"
#endif //BT_ENABLE_ENET
#ifdef __APPLE__
#include <Python/Python.h>
@@ -22,6 +24,7 @@ enum eCONNECT_METHOD {
eCONNECT_GUI = 1,
eCONNECT_DIRECT = 2,
eCONNECT_SHARED_MEMORY = 3,
eCONNECT_UDP = 4,
};
static PyObject* SpamError;
@@ -60,8 +63,8 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args) {
int method = eCONNECT_GUI;
if (!PyArg_ParseTuple(args, "i", &method)) {
PyErr_SetString(SpamError,
"connectPhysicsServer expected argument eCONNECT_GUI, "
"eCONNECT_DIRECT or eCONNECT_SHARED_MEMORY");
"connectPhysicsServer expected argument GUI, "
"DIRECT, SHARED_MEMORY or UDP");
return NULL;
}
@@ -85,6 +88,18 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args) {
sm = b3ConnectSharedMemory(SHARED_MEMORY_KEY);
break;
}
case eCONNECT_UDP:
{
#ifdef BT_ENABLE_ENET
sm = b3ConnectPhysicsUDP("localhost", 1234);
#else
PyErr_SetString(SpamError, "UDP is not enabled in this pybullet build");
return NULL;
#endif //BT_ENABLE_ENET
break;
}
default: {
PyErr_SetString(SpamError, "connectPhysicsServer unexpected argument");
@@ -2401,6 +2416,8 @@ initpybullet(void)
eCONNECT_SHARED_MEMORY); // user read
PyModule_AddIntConstant(m, "DIRECT", eCONNECT_DIRECT); // user read
PyModule_AddIntConstant(m, "GUI", eCONNECT_GUI); // user read
PyModule_AddIntConstant(m, "UDP", eCONNECT_UDP); // user read
PyModule_AddIntConstant(m, "TORQUE_CONTROL", CONTROL_MODE_TORQUE);
PyModule_AddIntConstant(m, "VELOCITY_CONTROL",