Merge pull request #979 from erwincoumans/master

fix lack of collision scaling in pybullet URDF/SDF files (only graphi…
This commit is contained in:
erwincoumans
2017-03-02 08:18:11 -08:00
committed by GitHub
191 changed files with 842617 additions and 12 deletions

View File

@@ -704,6 +704,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
}
btBvhTriangleMeshShape* trimesh = new btBvhTriangleMeshShape(meshInterface,true,true);
trimesh->setLocalScaling(collision->m_geometry.m_meshScale);
shape = trimesh;
} else
{
@@ -713,6 +714,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
convexHull->optimizeConvexHull();
//convexHull->initializePolyhedralFeatures();
convexHull->setMargin(gUrdfDefaultCollisionMargin);
convexHull->setLocalScaling(collision->m_geometry.m_meshScale);
shape = convexHull;
}
} else

View File

@@ -347,6 +347,16 @@ int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle comman
command->m_updateFlags |= SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD;
return 0;
}
int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHandle, int maxNumCmdPer1ms)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
command->m_physSimParamArgs.m_maxNumCmdPer1ms = maxNumCmdPer1ms;
command->m_updateFlags |= SIM_PARAM_MAX_CMD_PER_1MS;
return 0;
}
int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations)
{

View File

@@ -198,6 +198,7 @@ int b3PhysicsParamSetCollisionFilterMode(b3SharedMemoryCommandHandle commandHand
int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle, int useSplitImpulse);
int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandle commandHandle, double splitImpulsePenetrationThreshold);
int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold);
int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHandle, int maxNumCmdPer1ms);
//b3PhysicsParamSetInternalSimFlags is for internal/temporary/easter-egg/experimental demo purposes
//Use at own risk: magic things may or my not happen when calling this API

View File

@@ -48,6 +48,7 @@ bool gResetSimulation = 0;
int gVRTrackingObjectUniqueId = -1;
btTransform gVRTrackingObjectTr = btTransform::getIdentity();
int gMaxNumCmdPer1ms = 100;//experiment: add some delay to avoid threads starving other threads
int gCreateObjectSimVR = -1;
int gEnableKukaControl = 0;
btVector3 gVRTeleportPos1(0,0,0);
@@ -3162,6 +3163,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
{
gContactBreakingThreshold = clientCmd.m_physSimParamArgs.m_contactBreakingThreshold;
}
if (clientCmd.m_updateFlags&SIM_PARAM_MAX_CMD_PER_1MS)
{
gMaxNumCmdPer1ms = clientCmd.m_physSimParamArgs.m_maxNumCmdPer1ms;
}
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_COLLISION_FILTER_MODE)
{
m_data->m_broadphaseCollisionFilterCallback->m_filterMode = clientCmd.m_physSimParamArgs.m_collisionFilterMode;

View File

@@ -277,7 +277,7 @@ struct MotionThreadLocalStorage
float clampedDeltaTime = 0.2;
float sleepTimeThreshold = 8./1000.;
extern int gMaxNumCmdPer1ms;
void MotionThreadFunc(void* userPtr,void* lsMemory)
@@ -289,6 +289,7 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
//int workLeft = true;
b3Clock clock;
clock.reset();
b3Clock sleepClock;
bool init = true;
if (init)
{
@@ -299,6 +300,8 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
double deltaTimeInSeconds = 0;
int numCmdSinceSleep1ms = 0;
do
{
BT_PROFILE("loop");
@@ -307,6 +310,19 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
BT_PROFILE("usleep(0)");
b3Clock::usleep(0);
}
if (numCmdSinceSleep1ms>gMaxNumCmdPer1ms)
{
BT_PROFILE("usleep(1000)");
b3Clock::usleep(1000);
numCmdSinceSleep1ms = 0;
sleepClock.reset();
}
if (sleepClock.getTimeMilliseconds()>1)
{
sleepClock.reset();
numCmdSinceSleep1ms = 0;
}
double dt = double(clock.getTimeMicroseconds())/1000000.;
clock.reset();
deltaTimeInSeconds+= dt;
@@ -434,6 +450,7 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
{
BT_PROFILE("processClientCommands");
args->m_physicsServerPtr->processClientCommands();
numCmdSinceSleep1ms++;
}
} while (args->m_cs->getSharedParam(0)!=eRequestTerminateMotion);

View File

@@ -315,6 +315,7 @@ enum EnumSimParamUpdateFlags
SIM_PARAM_UPDATE_SPLIT_IMPULSE_PENETRATION_THRESHOLD = 256,
SIM_PARAM_UPDATE_COLLISION_FILTER_MODE=512,
SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD = 1024,
SIM_PARAM_MAX_CMD_PER_1MS = 2048,
};
enum EnumLoadBunnyUpdateFlags
@@ -342,6 +343,7 @@ struct SendPhysicsSimulationParameters
int m_useSplitImpulse;
double m_splitImpulsePenetrationThreshold;
double m_contactBreakingThreshold;
int m_maxNumCmdPer1ms;
int m_internalSimFlags;
double m_defaultContactERP;
int m_collisionFilterMode;

View File

@@ -4,7 +4,7 @@
#define SHARED_MEMORY_KEY 12347
///increase the SHARED_MEMORY_MAGIC_NUMBER whenever incompatible changes are made in the structures
///my convention is year/month/day/rev
#define SHARED_MEMORY_MAGIC_NUMBER 201702220
#define SHARED_MEMORY_MAGIC_NUMBER 201703010
enum EnumSharedMemoryClientCommand
{

View File

@@ -659,9 +659,11 @@ void CMainApplication::Shutdown()
}
}
sExample->exitPhysics();
delete sExample;
if (sExample)
{
sExample->exitPhysics();
delete sExample;
}
delete m_app;
m_app=0;

View File

@@ -536,6 +536,7 @@ LoadObj(
// material
std::map<std::string, material_t> material_map;
material_t material;
InitMaterial(material);
int maxchars = 8192; // Alloc enough size.
std::vector<char> buf(maxchars); // Alloc enough size.

View File

@@ -606,14 +606,14 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
int numSubSteps = -1;
int collisionFilterMode = -1;
double contactBreakingThreshold = -1;
int maxNumCmdPer1ms = -1;
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", "numSubSteps","collisionFilterMode", "contactBreakingThreshold", "physicsClientId", NULL };
static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", "numSubSteps","collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "physicsClientId", NULL };
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidi", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold,&numSubSteps,
&collisionFilterMode, &contactBreakingThreshold, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidii", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold,&numSubSteps,
&collisionFilterMode, &contactBreakingThreshold, &maxNumCmdPer1ms, &physicsClientId))
{
return NULL;
}
@@ -658,7 +658,10 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
{
b3PhysicsParamSetContactBreakingThreshold(command,contactBreakingThreshold);
}
if (maxNumCmdPer1ms>=0)
{
b3PhysicsParamSetMaxNumCommandsPer1ms(command,maxNumCmdPer1ms);
}
//ret = b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation);
@@ -3004,6 +3007,43 @@ static PyObject* pybullet_configureDebugVisualizer(PyObject* self, PyObject* arg
}
static PyObject* pybullet_resetDebugVisualizerCamera(PyObject* self, PyObject* args, PyObject *keywds)
{
float cameraDistance = -1;
float cameraYaw = -1;
float cameraPitch = -1;
PyObject* cameraTargetPosObj=0;
int physicsClientId = 0;
b3PhysicsClientHandle sm=0;
static char *kwlist[] = {"cameraDistance", "cameraYaw", "cameraPitch", "cameraTargetPosition", "physicsClientId", NULL };
if (!PyArg_ParseTupleAndKeywords(args, keywds, "fffO|i", kwlist,
&cameraDistance, &cameraYaw, &cameraPitch, &cameraTargetPosObj, &physicsClientId))
return NULL;
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
{
b3SharedMemoryCommandHandle commandHandle = b3InitConfigureOpenGLVisualizer(sm);
if ((cameraDistance>=0) && (cameraYaw>=0) && (cameraPitch>=0))
{
float cameraTargetPosition[3];
if (pybullet_internalSetVector(cameraTargetPosObj,cameraTargetPosition))
{
b3ConfigureOpenGLVisualizerSetViewMatrix(commandHandle,cameraDistance,cameraPitch, cameraYaw, cameraTargetPosition);
}
}
b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
}
Py_INCREF(Py_None);
return Py_None;
}
static PyObject* pybullet_setDebugObjectColor(PyObject* self, PyObject* args, PyObject *keywds)
{
@@ -5098,9 +5138,14 @@ static PyMethodDef SpamMethods[] = {
},
{ "configureDebugVisualizer", (PyCFunction)pybullet_configureDebugVisualizer, METH_VARARGS | METH_KEYWORDS,
"For the 3D OpenGL Visualizer, enable/disable GUI, shadows. Set the camera parameters."
"For the 3D OpenGL Visualizer, enable/disable GUI, shadows."
},
{ "resetDebugVisualizerCamera", (PyCFunction)pybullet_resetDebugVisualizerCamera, METH_VARARGS | METH_KEYWORDS,
"For the 3D OpenGL Visualizer, set the camera distance, yaw, pitch and target position."
},
{"getVisualShapeData", (PyCFunction)pybullet_getVisualShapeData, METH_VARARGS| METH_KEYWORDS,
"Return the visual shape information for one object." },

View File

@@ -11,6 +11,8 @@ import pybullet as p
#first try to connect to shared memory (VR), if it fails use local GUI
c = p.connect(p.SHARED_MEMORY)
if (c<0):
c = p.connect(p.GUI)
#p.resetSimulation()
p.setGravity(0,0,-10)
print(c)
@@ -51,7 +53,7 @@ def convertSensor(x):
b = (v-minV)/float(maxV-minV)
return (1.0-b)
ser = serial.Serial(port='COM3',baudrate=115200,parity=serial.PARITY_ODD,stopbits=serial.STOPBITS_TWO,bytesize=serial.SEVENBITS)
ser = serial.Serial(port='COM9',baudrate=115200,parity=serial.PARITY_ODD,stopbits=serial.STOPBITS_TWO,bytesize=serial.SEVENBITS)
if (ser.isOpen()):
while True:
events = p.getVREvents()