re-enable shared memory connection for pybullet Gym envs (with fallback to GUI or DIRECT)
suppress shared memory connection warnings add fallback from ER_BULLET_HARDWARE_OPENGL to TinyRenderer if not available
This commit is contained in:
@@ -78,7 +78,7 @@ struct PhysicsClientSharedMemoryInternalData {
|
|||||||
m_hasLastServerStatus(false),
|
m_hasLastServerStatus(false),
|
||||||
m_sharedMemoryKey(SHARED_MEMORY_KEY),
|
m_sharedMemoryKey(SHARED_MEMORY_KEY),
|
||||||
m_verboseOutput(false),
|
m_verboseOutput(false),
|
||||||
m_timeOutInSeconds(1e30)
|
m_timeOutInSeconds(5)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
void processServerStatus();
|
void processServerStatus();
|
||||||
@@ -311,7 +311,7 @@ bool PhysicsClientSharedMemory::connect() {
|
|||||||
m_data->m_isConnected = true;
|
m_data->m_isConnected = true;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
b3Warning("Cannot connect to shared memory");
|
//b3Warning("Cannot connect to shared memory");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#if 0
|
#if 0
|
||||||
|
|||||||
@@ -3541,7 +3541,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
bool handled = false;
|
||||||
|
|
||||||
if ((clientCmd.m_updateFlags & ER_BULLET_HARDWARE_OPENGL)!=0)
|
if ((clientCmd.m_updateFlags & ER_BULLET_HARDWARE_OPENGL)!=0)
|
||||||
{
|
{
|
||||||
|
|
||||||
@@ -3551,14 +3552,19 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
segmentationMaskBuffer, numRequestedPixels,
|
segmentationMaskBuffer, numRequestedPixels,
|
||||||
startPixelIndex,width,height,&numPixelsCopied);
|
startPixelIndex,width,height,&numPixelsCopied);
|
||||||
|
|
||||||
m_data->m_guiHelper->debugDisplayCameraImageData(viewMat,
|
if (numPixelsCopied>0)
|
||||||
|
{
|
||||||
|
handled = true;
|
||||||
|
m_data->m_guiHelper->debugDisplayCameraImageData(viewMat,
|
||||||
projMat,pixelRGBA,numRequestedPixels,
|
projMat,pixelRGBA,numRequestedPixels,
|
||||||
depthBuffer,numRequestedPixels,
|
depthBuffer,numRequestedPixels,
|
||||||
0, numRequestedPixels,
|
0, numRequestedPixels,
|
||||||
startPixelIndex,width,height,&numPixelsCopied);
|
startPixelIndex,width,height,&numPixelsCopied);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
} else
|
}
|
||||||
|
if (!handled)
|
||||||
{
|
{
|
||||||
|
|
||||||
if (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0)
|
if (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0)
|
||||||
|
|||||||
@@ -91,7 +91,7 @@ void* PosixSharedMemory::allocateSharedMemory(int key, int size, bool allowCr
|
|||||||
int id = shmget((key_t) key, (size_t) size,flags);
|
int id = shmget((key_t) key, (size_t) size,flags);
|
||||||
if (id < 0)
|
if (id < 0)
|
||||||
{
|
{
|
||||||
b3Warning("shmget error");
|
//b3Warning("shmget error1");
|
||||||
} else
|
} else
|
||||||
{
|
{
|
||||||
btPointerCaster result;
|
btPointerCaster result;
|
||||||
|
|||||||
@@ -8,7 +8,7 @@ class BulletClient(object):
|
|||||||
|
|
||||||
def __init__(self, connection_mode=pybullet.DIRECT):
|
def __init__(self, connection_mode=pybullet.DIRECT):
|
||||||
"""Create a simulation and connect to it."""
|
"""Create a simulation and connect to it."""
|
||||||
self._client = -1 #pybullet.connect(pybullet.SHARED_MEMORY)
|
self._client = pybullet.connect(pybullet.SHARED_MEMORY)
|
||||||
if(self._client<0):
|
if(self._client<0):
|
||||||
self._client = pybullet.connect(connection_mode)
|
self._client = pybullet.connect(connection_mode)
|
||||||
self._shapes = {}
|
self._shapes = {}
|
||||||
|
|||||||
@@ -40,7 +40,9 @@ class KukaCamGymEnv(gym.Env):
|
|||||||
self.terminated = 0
|
self.terminated = 0
|
||||||
self._p = p
|
self._p = p
|
||||||
if self._renders:
|
if self._renders:
|
||||||
p.connect(p.GUI)
|
cid = p.connect(p.SHARED_MEMORY)
|
||||||
|
if (cid<0):
|
||||||
|
p.connect(p.GUI)
|
||||||
p.resetDebugVisualizerCamera(1.3,180,-41,[0.52,-0.2,-0.33])
|
p.resetDebugVisualizerCamera(1.3,180,-41,[0.52,-0.2,-0.33])
|
||||||
else:
|
else:
|
||||||
p.connect(p.DIRECT)
|
p.connect(p.DIRECT)
|
||||||
|
|||||||
@@ -37,7 +37,7 @@ class KukaGymEnv(gym.Env):
|
|||||||
self.terminated = 0
|
self.terminated = 0
|
||||||
self._p = p
|
self._p = p
|
||||||
if self._renders:
|
if self._renders:
|
||||||
cid = -1 #p.connect(p.SHARED_MEMORY)
|
cid = p.connect(p.SHARED_MEMORY)
|
||||||
if (cid<0):
|
if (cid<0):
|
||||||
cid = p.connect(p.GUI)
|
cid = p.connect(p.GUI)
|
||||||
p.resetDebugVisualizerCamera(1.3,180,-41,[0.52,-0.2,-0.33])
|
p.resetDebugVisualizerCamera(1.3,180,-41,[0.52,-0.2,-0.33])
|
||||||
|
|||||||
@@ -39,7 +39,7 @@ class MJCFBaseBulletEnv(gym.Env):
|
|||||||
|
|
||||||
def _reset(self):
|
def _reset(self):
|
||||||
if (self.physicsClientId<0):
|
if (self.physicsClientId<0):
|
||||||
self.physicsClientId = -1 #p.connect(p.SHARED_MEMORY)
|
self.physicsClientId = p.connect(p.SHARED_MEMORY)
|
||||||
if (self.physicsClientId<0):
|
if (self.physicsClientId<0):
|
||||||
if (self.isRender):
|
if (self.isRender):
|
||||||
self.physicsClientId = p.connect(p.GUI)
|
self.physicsClientId = p.connect(p.GUI)
|
||||||
|
|||||||
@@ -13,6 +13,7 @@ p.connect(p.GUI_SERVER)
|
|||||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||||
|
|
||||||
while(1):
|
while(1):
|
||||||
|
#this is a no-op command, to allow GUI updates on Mac OSX (main thread)
|
||||||
|
p.setPhysicsEngineParameter()
|
||||||
time.sleep(0.01)
|
time.sleep(0.01)
|
||||||
p.getNumBodies()
|
|
||||||
|
|
||||||
|
|||||||
@@ -258,6 +258,7 @@ void testSharedMemory(b3PhysicsClientHandle sm)
|
|||||||
command = b3InitRequestCameraImage(sm);
|
command = b3InitRequestCameraImage(sm);
|
||||||
|
|
||||||
b3RequestCameraImageSetPixelResolution(command, width, height);
|
b3RequestCameraImageSetPixelResolution(command, width, height);
|
||||||
|
b3RequestCameraImageSelectRenderer(command,ER_BULLET_HARDWARE_OPENGL);
|
||||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -298,7 +299,10 @@ void testSharedMemory(b3PhysicsClientHandle sm)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
} else
|
||||||
|
{
|
||||||
|
b3Warning("Cannot submit commands.\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
b3DisconnectSharedMemory(sm);
|
b3DisconnectSharedMemory(sm);
|
||||||
|
|||||||
Reference in New Issue
Block a user