more PyBullet PhysX preliminary work.
This commit is contained in:
@@ -60,6 +60,11 @@
|
|||||||
description = "Statically link vr plugin (in examples/SharedMemory/plugins/vrSyncPlugin)"
|
description = "Statically link vr plugin (in examples/SharedMemory/plugins/vrSyncPlugin)"
|
||||||
}
|
}
|
||||||
|
|
||||||
|
newoption
|
||||||
|
{
|
||||||
|
trigger = "enable_physx",
|
||||||
|
description = "Allow optional PhysX backend for PyBullet, use pybullet.connect(pybullet.PhysX)."
|
||||||
|
}
|
||||||
|
|
||||||
newoption
|
newoption
|
||||||
{
|
{
|
||||||
@@ -638,4 +643,7 @@ end
|
|||||||
include "../src/BulletDynamics"
|
include "../src/BulletDynamics"
|
||||||
include "../src/BulletCollision"
|
include "../src/BulletCollision"
|
||||||
include "../src/LinearMath"
|
include "../src/LinearMath"
|
||||||
|
if _OPTIONS["enable_physx"] then
|
||||||
|
include "../src/physx"
|
||||||
|
end
|
||||||
|
|
||||||
|
|||||||
@@ -250,6 +250,7 @@ static void SimpleResizeCallback(float widthf, float heightf)
|
|||||||
// gApp->m_primRenderer->setScreenSize(width, height);
|
// gApp->m_primRenderer->setScreenSize(width, height);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if 0
|
||||||
static void SimpleKeyboardCallback(int key, int state)
|
static void SimpleKeyboardCallback(int key, int state)
|
||||||
{
|
{
|
||||||
if (key == B3G_ESCAPE) //&& gApp && gApp->m_window)
|
if (key == B3G_ESCAPE) //&& gApp && gApp->m_window)
|
||||||
@@ -261,7 +262,7 @@ static void SimpleKeyboardCallback(int key, int state)
|
|||||||
//gApp->defaultKeyboardCallback(key,state);
|
//gApp->defaultKeyboardCallback(key,state);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
static void SimpleMouseButtonCallback(int button, int state, float x, float y)
|
static void SimpleMouseButtonCallback(int button, int state, float x, float y)
|
||||||
{
|
{
|
||||||
if (gWindow)
|
if (gWindow)
|
||||||
|
|||||||
@@ -11,7 +11,7 @@ struct EGLRendererVisualShapeConverter : public UrdfRenderingInterface
|
|||||||
|
|
||||||
virtual ~EGLRendererVisualShapeConverter();
|
virtual ~EGLRendererVisualShapeConverter();
|
||||||
|
|
||||||
virtual int convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, int collisionObjectUniqueId, int bodyUniqueId, struct CommonFileIOInterface* fileIO);
|
virtual int convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, int orgGraphicsUniqueId, int bodyUniqueId, struct CommonFileIOInterface* fileIO);
|
||||||
|
|
||||||
virtual int getNumVisualShapes(int bodyUniqueId);
|
virtual int getNumVisualShapes(int bodyUniqueId);
|
||||||
|
|
||||||
|
|||||||
@@ -11,7 +11,7 @@ struct TinyRendererVisualShapeConverter : public UrdfRenderingInterface
|
|||||||
|
|
||||||
virtual ~TinyRendererVisualShapeConverter();
|
virtual ~TinyRendererVisualShapeConverter();
|
||||||
|
|
||||||
virtual int convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, int collisionObjectUniqueId, int bodyUniqueId, struct CommonFileIOInterface* fileIO);
|
virtual int convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, int unused, int bodyUniqueId, struct CommonFileIOInterface* fileIO);
|
||||||
|
|
||||||
virtual int getNumVisualShapes(int bodyUniqueId);
|
virtual int getNumVisualShapes(int bodyUniqueId);
|
||||||
|
|
||||||
|
|||||||
@@ -1,32 +1,14 @@
|
|||||||
import pybullet as p
|
import pybullet as p
|
||||||
import time
|
import time
|
||||||
|
|
||||||
#p.connect(p.DIRECT)
|
p.connect(p.PhysX)
|
||||||
#p.connect(p.DART)
|
p.loadPlugin("eglRendererPlugin")
|
||||||
p.connect(p.MuJoCo)
|
|
||||||
|
|
||||||
#p.connect(p.GUI)
|
|
||||||
bodies = p.loadMJCF("mjcf/capsule.xml")
|
|
||||||
print("bodies=",bodies)
|
|
||||||
|
|
||||||
numBodies = p.getNumBodies()
|
|
||||||
print("numBodies=",numBodies)
|
|
||||||
for i in range (numBodies):
|
|
||||||
print("bodyInfo[",i,"]=",p.getBodyInfo(i))
|
|
||||||
|
|
||||||
|
p.loadURDF("plane.urdf")
|
||||||
|
for i in range (50):
|
||||||
|
p.loadURDF("r2d2.urdf",[0,0,1+i*2])
|
||||||
p.setGravity(0,0,-10)
|
p.setGravity(0,0,-10)
|
||||||
timeStep = 1./240.
|
|
||||||
p.setPhysicsEngineParameter(fixedTimeStep=timeStep)
|
|
||||||
|
|
||||||
#while (p.isConnected()):
|
while (1):
|
||||||
for i in range (1000):
|
|
||||||
p.stepSimulation()
|
p.stepSimulation()
|
||||||
|
time.sleep(1./240.)
|
||||||
for b in bodies:
|
|
||||||
pos,orn=p.getBasePositionAndOrientation(b)
|
|
||||||
print("pos[",b,"]=",pos)
|
|
||||||
print("orn[",b,"]=",orn)
|
|
||||||
linvel,angvel=p.getBaseVelocity(b)
|
|
||||||
print("linvel[",b,"]=",linvel)
|
|
||||||
print("angvel[",b,"]=",angvel)
|
|
||||||
time.sleep(timeStep)
|
|
||||||
@@ -20,7 +20,7 @@ project ("pybullet")
|
|||||||
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
|
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
|
||||||
hasCL = findOpenCL("clew")
|
hasCL = findOpenCL("clew")
|
||||||
|
|
||||||
links{"BulletExampleBrowserLib","gwen", "BulletFileLoader","BulletWorldImporter","OpenGL_Window","BulletSoftBody", "BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision","LinearMath","BussIK", "Bullet3Common"}
|
links{ "BulletExampleBrowserLib","gwen", "BulletFileLoader","BulletWorldImporter","OpenGL_Window","BulletSoftBody", "BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision","LinearMath","BussIK", "Bullet3Common"}
|
||||||
initOpenGL()
|
initOpenGL()
|
||||||
initGlew()
|
initGlew()
|
||||||
|
|
||||||
@@ -172,6 +172,54 @@ if not _OPTIONS["no-enet"] then
|
|||||||
"../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h",
|
"../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h",
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if _OPTIONS["enable_physx"] then
|
||||||
|
defines {"BT_ENABLE_PHYSX","PX_PHYSX_STATIC_LIB", "PX_FOUNDATION_DLL=0"}
|
||||||
|
|
||||||
|
configuration {"x64", "debug"}
|
||||||
|
defines {"_DEBUG"}
|
||||||
|
configuration {"x86", "debug"}
|
||||||
|
defines {"_DEBUG"}
|
||||||
|
configuration {"x64", "release"}
|
||||||
|
defines {"NDEBUG"}
|
||||||
|
configuration {"x86", "release"}
|
||||||
|
defines {"NDEBUG"}
|
||||||
|
configuration{}
|
||||||
|
|
||||||
|
includedirs {
|
||||||
|
".",
|
||||||
|
"../../src/PhysX/physx/include",
|
||||||
|
"../../src/PhysX/physx/include/characterkinematic",
|
||||||
|
"../../src/PhysX/physx/include/common",
|
||||||
|
"../../src/PhysX/physx/include/cooking",
|
||||||
|
"../../src/PhysX/physx/include/extensions",
|
||||||
|
"../../src/PhysX/physx/include/geometry",
|
||||||
|
"../../src/PhysX/physx/include/geomutils",
|
||||||
|
"../../src/PhysX/physx/include/vehicle",
|
||||||
|
"../../src/PhysX/pxshared/include",
|
||||||
|
}
|
||||||
|
links {
|
||||||
|
"PhysX",
|
||||||
|
}
|
||||||
|
|
||||||
|
files {
|
||||||
|
"../../examples/SharedMemory/plugins/eglPlugin/eglRendererPlugin.cpp",
|
||||||
|
"../../examples/SharedMemory/plugins/eglPlugin/eglRendererPlugin.h",
|
||||||
|
"../../examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp",
|
||||||
|
"../../examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.h",
|
||||||
|
"../../examples/SharedMemory/physx/PhysXC_API.cpp",
|
||||||
|
"../../examples/SharedMemory/physx/PhysXClient.cpp",
|
||||||
|
"../../examples/SharedMemory/physx/PhysXServerCommandProcessor.cpp",
|
||||||
|
"../../examples/SharedMemory/physx/PhysXUrdfImporter.cpp",
|
||||||
|
"../../examples/SharedMemory/physx/URDF2PhysX.cpp",
|
||||||
|
"../../examples/SharedMemory/physx/PhysXC_API.h",
|
||||||
|
"../../examples/SharedMemory/physx/PhysXClient.h",
|
||||||
|
"../../examples/SharedMemory/physx/PhysXServerCommandProcessor.h",
|
||||||
|
"../../examples/SharedMemory/physx/PhysXUrdfImporter.h",
|
||||||
|
"../../examples/SharedMemory/physx/URDF2PhysX.h",
|
||||||
|
"../../examples/SharedMemory/physx/PhysXUserData.h",
|
||||||
|
}
|
||||||
|
end
|
||||||
|
|
||||||
if (_OPTIONS["enable_static_vr_plugin"]) then
|
if (_OPTIONS["enable_static_vr_plugin"]) then
|
||||||
files {"../../examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
|
files {"../../examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
|
||||||
end
|
end
|
||||||
|
|||||||
Reference in New Issue
Block a user