Merge pull request #1313 from erwincoumans/master

pybullet: remove memory of loadTexture, more reliable shutdown of shared memory when CTRL-C is used in ExampleBrowser
This commit is contained in:
erwincoumans
2017-09-13 15:12:25 -07:00
committed by GitHub
15 changed files with 87 additions and 23 deletions

View File

@@ -20,8 +20,50 @@
static double gMinUpdateTimeMicroSecs = 1000.; static double gMinUpdateTimeMicroSecs = 1000.;
static bool interrupted=false;
static OpenGLExampleBrowser* sExampleBrowser=0;
#ifndef _WIN32
#include <signal.h>
#include <err.h>
#include <unistd.h>
static void cleanup(int signo)
{
if (interrupted) { // this is the second time, we're hanging somewhere
// if (example) {
// example->abort();
// }
b3Printf("Aborting and deleting SharedMemoryCommon object");
sleep(1);
delete sExampleBrowser;
sExampleBrowser = 0;
errx(EXIT_FAILURE, "aborted example on signal %d", signo);
} else
{
b3Printf("no action");
}
interrupted = true;
warnx("caught signal %d", signo);
}
#endif//_WIN32
int main(int argc, char* argv[]) int main(int argc, char* argv[])
{ {
#ifndef _WIN32
struct sigaction action;
memset(&action, 0x0, sizeof(action));
action.sa_handler = cleanup;
static const int signos[] = { SIGHUP, SIGINT, SIGQUIT, SIGABRT, SIGSEGV, SIGPIPE, SIGTERM };
for (int ii(0); ii < sizeof(signos) / sizeof(*signos); ++ii) {
if (0 != sigaction(signos[ii], &action, NULL)) {
err(EXIT_FAILURE, "signal %d", signos[ii]);
}
}
#endif
{ {
b3CommandLineArgs args(argc, argv); b3CommandLineArgs args(argc, argv);
b3Clock clock; b3Clock clock;
@@ -31,6 +73,7 @@ int main(int argc, char* argv[])
examples.initExampleEntries(); examples.initExampleEntries();
OpenGLExampleBrowser* exampleBrowser = new OpenGLExampleBrowser(&examples); OpenGLExampleBrowser* exampleBrowser = new OpenGLExampleBrowser(&examples);
sExampleBrowser = exampleBrowser;//for <CTRL-C> etc, cleanup shared memory
bool init = exampleBrowser->init(argc, argv); bool init = exampleBrowser->init(argc, argv);
exampleBrowser->registerFileImporter(".urdf", ImportURDFCreateFunc); exampleBrowser->registerFileImporter(".urdf", ImportURDFCreateFunc);
exampleBrowser->registerFileImporter(".sdf", ImportSDFCreateFunc); exampleBrowser->registerFileImporter(".sdf", ImportSDFCreateFunc);
@@ -57,7 +100,7 @@ int main(int argc, char* argv[])
clock.reset(); clock.reset();
exampleBrowser->update(deltaTimeInSeconds); exampleBrowser->update(deltaTimeInSeconds);
} }
} while (!exampleBrowser->requestedExit()); } while (!exampleBrowser->requestedExit() && !interrupted);
} }
delete exampleBrowser; delete exampleBrowser;

View File

@@ -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

View File

@@ -3541,6 +3541,7 @@ 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);
if (numPixelsCopied>0)
{
handled = true;
m_data->m_guiHelper->debugDisplayCameraImageData(viewMat, 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)

View File

@@ -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;

View File

@@ -86,7 +86,7 @@ public:
b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, char* argv[]) b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, char* argv[])
{ {
InProcessPhysicsClientSharedMemoryMainThread* cl = new InProcessPhysicsClientSharedMemoryMainThread(argc, argv, 1); InProcessPhysicsClientSharedMemoryMainThread* cl = new InProcessPhysicsClientSharedMemoryMainThread(argc, argv, 1);
cl->setSharedMemoryKey(SHARED_MEMORY_KEY); cl->setSharedMemoryKey(SHARED_MEMORY_KEY+1);
cl->connect(); cl->connect();
return (b3PhysicsClientHandle ) cl; return (b3PhysicsClientHandle ) cl;
} }
@@ -94,7 +94,7 @@ b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int arg
b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory(int argc, char* argv[]) b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory(int argc, char* argv[])
{ {
InProcessPhysicsClientSharedMemoryMainThread* cl = new InProcessPhysicsClientSharedMemoryMainThread(argc, argv, 0); InProcessPhysicsClientSharedMemoryMainThread* cl = new InProcessPhysicsClientSharedMemoryMainThread(argc, argv, 0);
cl->setSharedMemoryKey(SHARED_MEMORY_KEY); cl->setSharedMemoryKey(SHARED_MEMORY_KEY+1);
cl->connect(); cl->connect();
return (b3PhysicsClientHandle ) cl; return (b3PhysicsClientHandle ) cl;
} }

View File

@@ -1081,6 +1081,11 @@ void TinyRendererVisualShapeConverter::resetAll()
} }
} }
for (int i=0;i<m_data->m_textures.size();i++)
{
free(m_data->m_textures[i].textureData);
}
m_data->m_textures.clear();
m_data->m_swRenderInstances.clear(); m_data->m_swRenderInstances.clear();
m_data->m_visualShapes.clear(); m_data->m_visualShapes.clear();
} }

View File

@@ -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 = {}

View File

@@ -40,6 +40,8 @@ class KukaCamGymEnv(gym.Env):
self.terminated = 0 self.terminated = 0
self._p = p self._p = p
if self._renders: if self._renders:
cid = p.connect(p.SHARED_MEMORY)
if (cid<0):
p.connect(p.GUI) 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:

View File

@@ -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])

View File

@@ -278,7 +278,7 @@ class MinitaurBulletEnv(gym.Env):
nearVal=0.1, farVal=100.0) nearVal=0.1, farVal=100.0)
(_, _, px, _, _) = self._pybullet_client.getCameraImage( (_, _, px, _, _) = self._pybullet_client.getCameraImage(
width=RENDER_WIDTH, height=RENDER_HEIGHT, viewMatrix=view_matrix, width=RENDER_WIDTH, height=RENDER_HEIGHT, viewMatrix=view_matrix,
projectionMatrix=proj_matrix) projectionMatrix=proj_matrix, renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
rgb_array = np.array(px) rgb_array = np.array(px)
rgb_array = rgb_array[:, :, :3] rgb_array = rgb_array[:, :, :3]
return rgb_array return rgb_array

View File

@@ -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)
@@ -82,7 +82,7 @@ class MJCFBaseBulletEnv(gym.Env):
(_, _, px, _, _) = p.getCameraImage( (_, _, px, _, _) = p.getCameraImage(
width=self._render_width, height=self._render_height, viewMatrix=view_matrix, width=self._render_width, height=self._render_height, viewMatrix=view_matrix,
projectionMatrix=proj_matrix, projectionMatrix=proj_matrix,
#renderer=p.ER_BULLET_HARDWARE_OPENGL renderer=p.ER_BULLET_HARDWARE_OPENGL
) )
rgb_array = np.array(px) rgb_array = np.array(px)
rgb_array = rgb_array[:, :, :3] rgb_array = rgb_array[:, :, :3]

View File

@@ -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()

View File

@@ -440,13 +440,16 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
command = b3InitSyncBodyInfoCommand(sm); command = b3InitSyncBodyInfoCommand(sm);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle); statusType = b3GetStatusType(statusHandle);
#if 0
if (statusType != CMD_BODY_INFO_COMPLETED) if (statusType != CMD_BODY_INFO_COMPLETED)
{ {
PyErr_SetString(SpamError, "b3InitSyncBodyInfoCommand failed."); printf("Connection terminated, couldn't get body info\n");
return NULL; b3DisconnectSharedMemory(sm);
sm = 0;
sPhysicsClients1[freeIndex] = 0;
sPhysicsClientsGUI[freeIndex] = 0;
sNumPhysicsClients++;
return -1;
} }
#endif
} }
} }
return PyInt_FromLong(freeIndex); return PyInt_FromLong(freeIndex);

View File

@@ -440,7 +440,7 @@ print("-----")
setup( setup(
name = 'pybullet', name = 'pybullet',
version='1.3.8', version='1.4.0',
description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning', description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.', long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
url='https://github.com/bulletphysics/bullet3', url='https://github.com/bulletphysics/bullet3',

View File

@@ -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,6 +299,9 @@ void testSharedMemory(b3PhysicsClientHandle sm)
} }
} }
} else
{
b3Warning("Cannot submit commands.\n");
} }