add sigaction handler to Example Browser, to always shutdown shared memory

make GUI_SERVER more reliable
next attempt to connect to SHARED_MEMORY in Gym envs, if available, before DIRECT/GUI
allow software rendering fallback, even if ER_BULLET_HARDWARE_OPENGL is chosen in getCameraImage
This commit is contained in:
Erwin Coumans
2017-09-13 13:30:16 -07:00
parent c250a5f0b9
commit 340a8f4704
6 changed files with 57 additions and 10 deletions

View File

@@ -20,8 +20,51 @@
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)
{
printf("SIG cleanup: %d\n", 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[])
{
#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);
b3Clock clock;
@@ -31,6 +74,7 @@ int main(int argc, char* argv[])
examples.initExampleEntries();
OpenGLExampleBrowser* exampleBrowser = new OpenGLExampleBrowser(&examples);
sExampleBrowser = exampleBrowser;//for <CTRL-C> etc, cleanup shared memory
bool init = exampleBrowser->init(argc, argv);
exampleBrowser->registerFileImporter(".urdf", ImportURDFCreateFunc);
exampleBrowser->registerFileImporter(".sdf", ImportSDFCreateFunc);
@@ -57,7 +101,7 @@ int main(int argc, char* argv[])
clock.reset();
exampleBrowser->update(deltaTimeInSeconds);
}
} while (!exampleBrowser->requestedExit());
} while (!exampleBrowser->requestedExit() && !interrupted);
}
delete exampleBrowser;

View File

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

View File

@@ -278,7 +278,7 @@ class MinitaurBulletEnv(gym.Env):
nearVal=0.1, farVal=100.0)
(_, _, px, _, _) = self._pybullet_client.getCameraImage(
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 = rgb_array[:, :, :3]
return rgb_array

View File

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

View File

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

View File

@@ -440,7 +440,7 @@ print("-----")
setup(
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',
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',