Merge pull request #947 from erwincoumans/master

[pybullet] add some out-of-bounds checks, reduce run-time memory allocations
This commit is contained in:
erwincoumans
2017-02-07 12:07:40 -08:00
committed by GitHub
5 changed files with 97 additions and 48 deletions

View File

@@ -444,10 +444,12 @@ int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle,
{ {
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command); b3Assert(command);
command->m_sendDesiredStateCommandArgument.m_desiredStateQ[qIndex] = value; if ((qIndex>=0) && (qIndex < MAX_DEGREE_OF_FREEDOM))
command->m_updateFlags |= SIM_DESIRED_STATE_HAS_Q; {
command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[qIndex] |= SIM_DESIRED_STATE_HAS_Q; command->m_sendDesiredStateCommandArgument.m_desiredStateQ[qIndex] = value;
command->m_updateFlags |= SIM_DESIRED_STATE_HAS_Q;
command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[qIndex] |= SIM_DESIRED_STATE_HAS_Q;
}
return 0; return 0;
} }
@@ -455,8 +457,7 @@ int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex,
{ {
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command); b3Assert(command);
b3Assert(dofIndex>=0); if ((dofIndex>=0) && (dofIndex < MAX_DEGREE_OF_FREEDOM))
if (dofIndex>=0)
{ {
command->m_sendDesiredStateCommandArgument.m_Kp[dofIndex] = value; command->m_sendDesiredStateCommandArgument.m_Kp[dofIndex] = value;
command->m_updateFlags |= SIM_DESIRED_STATE_HAS_KP; command->m_updateFlags |= SIM_DESIRED_STATE_HAS_KP;
@@ -469,8 +470,7 @@ int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex,
{ {
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command); b3Assert(command);
b3Assert(dofIndex>=0); if ((dofIndex>=0) && (dofIndex < MAX_DEGREE_OF_FREEDOM))
if (dofIndex>=0)
{ {
command->m_sendDesiredStateCommandArgument.m_Kd[dofIndex] = value; command->m_sendDesiredStateCommandArgument.m_Kd[dofIndex] = value;
command->m_updateFlags |= SIM_DESIRED_STATE_HAS_KD; command->m_updateFlags |= SIM_DESIRED_STATE_HAS_KD;
@@ -483,8 +483,7 @@ int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle,
{ {
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command); b3Assert(command);
b3Assert(dofIndex>=0); if ((dofIndex>=0) && (dofIndex < MAX_DEGREE_OF_FREEDOM))
if (dofIndex>=0)
{ {
command->m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex] = value; command->m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex] = value;
command->m_updateFlags |= SIM_DESIRED_STATE_HAS_QDOT; command->m_updateFlags |= SIM_DESIRED_STATE_HAS_QDOT;
@@ -498,8 +497,7 @@ int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int
{ {
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command); b3Assert(command);
b3Assert(dofIndex>=0); if ((dofIndex>=0) && (dofIndex < MAX_DEGREE_OF_FREEDOM))
if (dofIndex>=0)
{ {
command->m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex] = value; command->m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex] = value;
command->m_updateFlags |= SIM_DESIRED_STATE_HAS_MAX_FORCE; command->m_updateFlags |= SIM_DESIRED_STATE_HAS_MAX_FORCE;
@@ -512,8 +510,7 @@ int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandl
{ {
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command); b3Assert(command);
b3Assert(dofIndex>=0); if ((dofIndex>=0) && (dofIndex < MAX_DEGREE_OF_FREEDOM))
if (dofIndex>=0)
{ {
command->m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex] = value; command->m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex] = value;
command->m_updateFlags |= SIM_DESIRED_STATE_HAS_MAX_FORCE; command->m_updateFlags |= SIM_DESIRED_STATE_HAS_MAX_FORCE;
@@ -547,13 +544,16 @@ int b3GetJointState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle
bool result = b3GetJointInfo(physClient, bodyIndex,jointIndex, &info); bool result = b3GetJointInfo(physClient, bodyIndex,jointIndex, &info);
if (result) if (result)
{ {
state->m_jointPosition = status->m_sendActualStateArgs.m_actualStateQ[info.m_qIndex]; if ((info.m_qIndex>=0) && (info.m_uIndex>=0) && (info.m_qIndex < MAX_DEGREE_OF_FREEDOM) && (info.m_uIndex < MAX_DEGREE_OF_FREEDOM))
state->m_jointVelocity = status->m_sendActualStateArgs.m_actualStateQdot[info.m_uIndex]; {
for (int ii(0); ii < 6; ++ii) { state->m_jointPosition = status->m_sendActualStateArgs.m_actualStateQ[info.m_qIndex];
state->m_jointForceTorque[ii] = status->m_sendActualStateArgs.m_jointReactionForces[6 * jointIndex + ii]; state->m_jointVelocity = status->m_sendActualStateArgs.m_actualStateQdot[info.m_uIndex];
for (int ii(0); ii < 6; ++ii) {
state->m_jointForceTorque[ii] = status->m_sendActualStateArgs.m_jointReactionForces[6 * jointIndex + ii];
}
state->m_jointMotorTorque = status->m_sendActualStateArgs.m_jointMotorForce[jointIndex];
return 1;
} }
state->m_jointMotorTorque = status->m_sendActualStateArgs.m_jointMotorForce[jointIndex];
return 1;
} }
} }
return 0; return 0;

View File

@@ -1,5 +1,6 @@
#include "SharedMemoryInProcessPhysicsC_API.h" #include "SharedMemoryInProcessPhysicsC_API.h"
#include "../Utils/b3Clock.h"
#include "PhysicsClientSharedMemory.h" #include "PhysicsClientSharedMemory.h"
#include"../ExampleBrowser/InProcessExampleBrowser.h" #include"../ExampleBrowser/InProcessExampleBrowser.h"
@@ -8,7 +9,8 @@
class InProcessPhysicsClientSharedMemoryMainThread : public PhysicsClientSharedMemory class InProcessPhysicsClientSharedMemoryMainThread : public PhysicsClientSharedMemory
{ {
btInProcessExampleBrowserMainThreadInternalData* m_data; btInProcessExampleBrowserMainThreadInternalData* m_data;
b3Clock m_clock;
public: public:
InProcessPhysicsClientSharedMemoryMainThread(int argc, char* argv[]) InProcessPhysicsClientSharedMemoryMainThread(int argc, char* argv[])
@@ -41,9 +43,16 @@ public:
{ {
PhysicsClientSharedMemory::disconnectSharedMemory(); PhysicsClientSharedMemory::disconnectSharedMemory();
} }
unsigned long int ms = m_clock.getTimeMilliseconds();
btUpdateInProcessExampleBrowserMainThread(m_data); if (ms>20)
return PhysicsClientSharedMemory::processServerStatus(); {
m_clock.reset();
btUpdateInProcessExampleBrowserMainThread(m_data);
} else
{
//b3Clock::usleep(100);
}
return PhysicsClientSharedMemory::processServerStatus();
} }

View File

@@ -2,6 +2,8 @@ import pybullet as p
import time import time
import math import math
useRealTime = 0
fixedTimeStep = 0.001
physId = p.connect(p.SHARED_MEMORY) physId = p.connect(p.SHARED_MEMORY)
if (physId<0): if (physId<0):
@@ -9,8 +11,10 @@ if (physId<0):
p.loadURDF("plane.urdf") p.loadURDF("plane.urdf")
p.setGravity(0,0,-1) p.setGravity(0,0,-1)
p.setTimeStep(fixedTimeStep)
p.setRealTimeSimulation(0) p.setRealTimeSimulation(0)
quadruped = p.loadURDF("quadruped/quadruped.urdf",1,-2,2) quadruped = p.loadURDF("quadruped/quadruped.urdf",1,-2,1)
#p.getNumJoints(1) #p.getNumJoints(1)
#right front leg #right front leg
p.resetJointState(quadruped,0,1.57) p.resetJointState(quadruped,0,1.57)
@@ -71,24 +75,41 @@ p.setJointMotorControl(quadruped,23,p.VELOCITY_CONTROL,0,0)
p_gain = 2 p_gain =1
speed = 10 speed = 10
amplitude = 1.3 amplitude = 1.3
#stand still #stand still
t_end = time.time() + 2 p.setRealTimeSimulation(useRealTime)
while time.time() < t_end:
p.stepSimulation()
t=0.0
ref_time = time.time()
t_end = t + 4
while t < t_end:
if (useRealTime==0):
t = t+fixedTimeStep
p.stepSimulation()
else:
t = time.time()-ref_time
p.setGravity(0,0,-1)
p.setGravity(0,0,-10) p.setGravity(0,0,-10)
jump_amp = 0.5 jump_amp = 0.5
#jump #jump
t_end = time.time() + 10 t = 0.0
t_end = t + 10
i=0 i=0
t=0 ref_time = time.time()
while time.time() < t_end:
t = time.time() while t < t_end:
if (useRealTime):
t = time.time()-ref_time
else:
t = t+fixedTimeStep
p.setJointMotorControl(quadruped,0,p.POSITION_CONTROL,math.sin(t*speed)*jump_amp+1.57,p_gain) p.setJointMotorControl(quadruped,0,p.POSITION_CONTROL,math.sin(t*speed)*jump_amp+1.57,p_gain)
p.setJointMotorControl(quadruped,3,p.POSITION_CONTROL,-math.sin(t*speed)*jump_amp-1.57,p_gain) p.setJointMotorControl(quadruped,3,p.POSITION_CONTROL,-math.sin(t*speed)*jump_amp-1.57,p_gain)
p.setJointMotorControl(quadruped,6,p.POSITION_CONTROL,math.sin(t*speed)*jump_amp+1.57,p_gain) p.setJointMotorControl(quadruped,6,p.POSITION_CONTROL,math.sin(t*speed)*jump_amp+1.57,p_gain)
@@ -97,15 +118,19 @@ while time.time() < t_end:
p.setJointMotorControl(quadruped,15,p.POSITION_CONTROL,-math.sin(t*speed)*jump_amp-1.57,p_gain) p.setJointMotorControl(quadruped,15,p.POSITION_CONTROL,-math.sin(t*speed)*jump_amp-1.57,p_gain)
p.setJointMotorControl(quadruped,18,p.POSITION_CONTROL,math.sin(t*speed)*jump_amp+1.57,p_gain) p.setJointMotorControl(quadruped,18,p.POSITION_CONTROL,math.sin(t*speed)*jump_amp+1.57,p_gain)
p.setJointMotorControl(quadruped,21,p.POSITION_CONTROL,-math.sin(t*speed)*jump_amp-1.57,p_gain) p.setJointMotorControl(quadruped,21,p.POSITION_CONTROL,-math.sin(t*speed)*jump_amp-1.57,p_gain)
if (useRealTime==0):
p.stepSimulation() p.stepSimulation()
#hop forward #hop forward
t_end = time.time() + 30 t_end = 20
i=0 i=0
while time.time() < t_end: while t < t_end:
t = time.time() if (useRealTime):
t = time.time()-ref_time
else:
t = t+fixedTimeStep
p.setJointMotorControl(quadruped,0,p.POSITION_CONTROL,math.sin(t*speed)*amplitude+1.57,p_gain) p.setJointMotorControl(quadruped,0,p.POSITION_CONTROL,math.sin(t*speed)*amplitude+1.57,p_gain)
p.setJointMotorControl(quadruped,3,p.POSITION_CONTROL,-1.57,p_gain) p.setJointMotorControl(quadruped,3,p.POSITION_CONTROL,-1.57,p_gain)
p.setJointMotorControl(quadruped,6,p.POSITION_CONTROL,math.sin(t*speed)*amplitude+1.57,p_gain) p.setJointMotorControl(quadruped,6,p.POSITION_CONTROL,math.sin(t*speed)*amplitude+1.57,p_gain)
@@ -114,14 +139,18 @@ while time.time() < t_end:
p.setJointMotorControl(quadruped,15,p.POSITION_CONTROL,-1.57,p_gain) p.setJointMotorControl(quadruped,15,p.POSITION_CONTROL,-1.57,p_gain)
p.setJointMotorControl(quadruped,18,p.POSITION_CONTROL,math.sin(t*speed+3.14)*amplitude+1.57,p_gain) p.setJointMotorControl(quadruped,18,p.POSITION_CONTROL,math.sin(t*speed+3.14)*amplitude+1.57,p_gain)
p.setJointMotorControl(quadruped,21,p.POSITION_CONTROL,-1.57,p_gain) p.setJointMotorControl(quadruped,21,p.POSITION_CONTROL,-1.57,p_gain)
if (useRealTime==0):
p.stepSimulation() p.stepSimulation()
#walk #walk
t_end = time.time() + 120 t_end = 100
i=0 i=0
while time.time() < t_end: while t < t_end:
t = time.time() if (useRealTime):
t = time.time()-ref_time
else:
t = t+fixedTimeStep
p.setJointMotorControl(quadruped,0,p.POSITION_CONTROL,math.sin(t*3)*.3+1.57,1) p.setJointMotorControl(quadruped,0,p.POSITION_CONTROL,math.sin(t*3)*.3+1.57,1)
p.setJointMotorControl(quadruped,3,p.POSITION_CONTROL,-1.57,1) p.setJointMotorControl(quadruped,3,p.POSITION_CONTROL,-1.57,1)
p.setJointMotorControl(quadruped,6,p.POSITION_CONTROL,math.sin(t*3+0.5*3.14)*.3+1.57,1) p.setJointMotorControl(quadruped,6,p.POSITION_CONTROL,math.sin(t*3+0.5*3.14)*.3+1.57,1)

View File

@@ -24,6 +24,8 @@ subject to the following restrictions:
#include "BulletCollision/CollisionDispatch/btManifoldResult.h" #include "BulletCollision/CollisionDispatch/btManifoldResult.h"
#include "BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h" #include "BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h"
//USE_LOCAL_STACK will avoid most (often all) dynamic memory allocations due to resizing in processCollision and MycollideTT
#define USE_LOCAL_STACK 1
btShapePairCallback gCompoundCompoundChildShapePairCallback = 0; btShapePairCallback gCompoundCompoundChildShapePairCallback = 0;
@@ -251,7 +253,12 @@ static inline void MycollideTT( const btDbvtNode* root0,
int depth=1; int depth=1;
int treshold=btDbvt::DOUBLE_STACKSIZE-4; int treshold=btDbvt::DOUBLE_STACKSIZE-4;
btAlignedObjectArray<btDbvt::sStkNN> stkStack; btAlignedObjectArray<btDbvt::sStkNN> stkStack;
#ifdef USE_LOCAL_STACK
ATTRIBUTE_ALIGNED16(btDbvt::sStkNN localStack[btDbvt::DOUBLE_STACKSIZE]);
stkStack.initializeFromBuffer(&localStack,btDbvt::DOUBLE_STACKSIZE,btDbvt::DOUBLE_STACKSIZE);
#else
stkStack.resize(btDbvt::DOUBLE_STACKSIZE); stkStack.resize(btDbvt::DOUBLE_STACKSIZE);
#endif
stkStack[0]=btDbvt::sStkNN(root0,root1); stkStack[0]=btDbvt::sStkNN(root0,root1);
do { do {
btDbvt::sStkNN p=stkStack[--depth]; btDbvt::sStkNN p=stkStack[--depth];
@@ -329,6 +336,10 @@ void btCompoundCompoundCollisionAlgorithm::processCollision (const btCollisionOb
{ {
int i; int i;
btManifoldArray manifoldArray; btManifoldArray manifoldArray;
#ifdef USE_LOCAL_STACK
btPersistentManifold localManifolds[4];
manifoldArray.initializeFromBuffer(&localManifolds,0,4);
#endif
btSimplePairArray& pairs = m_childCollisionAlgorithmCache->getOverlappingPairArray(); btSimplePairArray& pairs = m_childCollisionAlgorithmCache->getOverlappingPairArray();
for (i=0;i<pairs.size();i++) for (i=0;i<pairs.size();i++)
{ {

View File

@@ -332,10 +332,10 @@ struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager::
} }
} }
if (m_solverInfo->m_minimumSolverBatchSize<=1) //if (m_solverInfo->m_minimumSolverBatchSize<=1)
{ //{
m_solver->solveGroup( bodies,numBodies,manifolds, numManifolds,startConstraint,numCurConstraints,*m_solverInfo,m_debugDrawer,m_dispatcher); // m_solver->solveGroup( bodies,numBodies,manifolds, numManifolds,startConstraint,numCurConstraints,*m_solverInfo,m_debugDrawer,m_dispatcher);
} else //} else
{ {
for (i=0;i<numBodies;i++) for (i=0;i<numBodies;i++)