Merge pull request #2077 from erwincoumans/master

fix regression in resetJointState for 1-DOF/3-DOF joints, more PyBullet-PhysX work
This commit is contained in:
erwincoumans
2019-01-26 18:44:38 -08:00
committed by GitHub
8 changed files with 97 additions and 41 deletions

View File

@@ -59,7 +59,12 @@
trigger = "enable_static_vr_plugin",
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
{
@@ -638,4 +643,7 @@ end
include "../src/BulletDynamics"
include "../src/BulletCollision"
include "../src/LinearMath"
if _OPTIONS["enable_physx"] then
include "../src/physx"
end

View File

@@ -68,6 +68,7 @@
#endif //SKIP_STATIC_PD_CONTROL_PLUGIN
#ifdef STATIC_LINK_SPD_PLUGIN
#include "plugins/stablePDPlugin/BulletConversion.h"
#include "plugins/stablePDPlugin/RBDModel.h"
@@ -8299,15 +8300,23 @@ bool PhysicsServerCommandProcessor::processInitPoseCommand(const struct SharedMe
}
if (hasPosVar)
{
btQuaternion q(
clientCmd.m_initPoseArgs.m_initialStateQ[posVarCountIndex],
clientCmd.m_initPoseArgs.m_initialStateQ[posVarCountIndex+1],
clientCmd.m_initPoseArgs.m_initialStateQ[posVarCountIndex+2],
clientCmd.m_initPoseArgs.m_initialStateQ[posVarCountIndex+3]);
q.normalize();
mb->setJointPosMultiDof(i, &q[0]);
double vel[6] = { 0, 0, 0, 0, 0, 0 };
mb->setJointVelMultiDof(i, vel);
if (mb->getLink(i).m_dofCount == 1)
{
mb->setJointPos(i, clientCmd.m_initPoseArgs.m_initialStateQ[posVarCountIndex]);
mb->setJointVel(i, 0);//backwards compatibility
}
if (mb->getLink(i).m_dofCount == 3)
{
btQuaternion q(
clientCmd.m_initPoseArgs.m_initialStateQ[posVarCountIndex],
clientCmd.m_initPoseArgs.m_initialStateQ[posVarCountIndex + 1],
clientCmd.m_initPoseArgs.m_initialStateQ[posVarCountIndex + 2],
clientCmd.m_initPoseArgs.m_initialStateQ[posVarCountIndex + 3]);
q.normalize();
mb->setJointPosMultiDof(i, &q[0]);
double vel[6] = { 0, 0, 0, 0, 0, 0 };
mb->setJointVelMultiDof(i, vel);
}
}
bool hasVel = true;
@@ -8322,7 +8331,15 @@ bool PhysicsServerCommandProcessor::processInitPoseCommand(const struct SharedMe
if (hasVel)
{
mb->setJointVelMultiDof(i, &clientCmd.m_initPoseArgs.m_initialStateQdot[uDofIndex]);
if (mb->getLink(i).m_dofCount == 1)
{
btScalar vel = clientCmd.m_initPoseArgs.m_initialStateQdot[uDofIndex];
mb->setJointVel(i, vel);
}
if (mb->getLink(i).m_dofCount == 3)
{
mb->setJointVelMultiDof(i, &clientCmd.m_initPoseArgs.m_initialStateQdot[uDofIndex]);
}
}
posVarCountIndex += mb->getLink(i).m_posVarCount;

View File

@@ -250,6 +250,7 @@ static void SimpleResizeCallback(float widthf, float heightf)
// gApp->m_primRenderer->setScreenSize(width, height);
}
#if 0
static void SimpleKeyboardCallback(int key, int state)
{
if (key == B3G_ESCAPE) //&& gApp && gApp->m_window)
@@ -261,7 +262,7 @@ static void SimpleKeyboardCallback(int key, int state)
//gApp->defaultKeyboardCallback(key,state);
}
}
#endif
static void SimpleMouseButtonCallback(int button, int state, float x, float y)
{
if (gWindow)

View File

@@ -11,7 +11,7 @@ struct EGLRendererVisualShapeConverter : public UrdfRenderingInterface
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);

View File

@@ -7,7 +7,7 @@ bool cShape::ParseShape(const std::string& str, eShape& out_shape)
bool succ = true;
if (str == "null")
{
out_shape = eShapeNull;
out_shape = eShapeNull;
}
else if (str == "box")
{

View File

@@ -11,7 +11,7 @@ struct TinyRendererVisualShapeConverter : public UrdfRenderingInterface
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);

View File

@@ -1,32 +1,14 @@
import pybullet as p
import time
#p.connect(p.DIRECT)
#p.connect(p.DART)
p.connect(p.MuJoCo)
p.connect(p.PhysX)
p.loadPlugin("eglRendererPlugin")
#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)
timeStep = 1./240.
p.setPhysicsEngineParameter(fixedTimeStep=timeStep)
#while (p.isConnected()):
for i in range (1000):
while (1):
p.stepSimulation()
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)
time.sleep(1./240.)

View File

@@ -20,7 +20,7 @@ project ("pybullet")
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
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()
initGlew()
@@ -171,7 +171,55 @@ if not _OPTIONS["no-enet"] then
"../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp",
"../../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
files {"../../examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
end