embed TCP graphics server in PyBullet for easier working-from-home

This allows to render at a different machine, sending all assets across the TCP network, using port 6667 by default.
You can use ssh port forwarding to get this working:
ssh -R 6667:localhost:6667 username@remotehost.com -v

python3 -m pybullet_utils.graphicsServer
python3 -m pybullet_utils.graphicsClient

Note that there are still some tcp networking issues that can cause a hang, just restart graphics server and graphics client if it hangs.
This commit is contained in:
Erwin Coumans
2020-03-20 15:43:52 -07:00
parent c06859723b
commit 344bd629ee
15 changed files with 1421 additions and 25 deletions

View File

@@ -152,10 +152,16 @@ class InProcessPhysicsClientExistingExampleBrowser : public PhysicsClientSharedM
SharedMemoryInterface* m_sharedMem;
b3Clock m_clock;
unsigned long long int m_prevTime;
struct GUIHelperInterface* m_guiHelper;
public:
InProcessPhysicsClientExistingExampleBrowser(struct GUIHelperInterface* guiHelper, bool useInProcessMemory, bool skipGraphicsUpdate)
InProcessPhysicsClientExistingExampleBrowser(struct GUIHelperInterface* guiHelper, bool useInProcessMemory, bool skipGraphicsUpdate, bool ownsGuiHelper)
{
if (ownsGuiHelper)
{
m_guiHelper = guiHelper;
}
m_sharedMem = 0;
CommonExampleOptions options(guiHelper);
@@ -179,6 +185,7 @@ public:
//s_instancingRenderer->removeAllInstances();
delete m_physicsServerExample;
delete m_sharedMem;
delete m_guiHelper;
}
// return non-null if there is a status, nullptr otherwise
@@ -257,7 +264,7 @@ B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingEx
bool useInprocessMemory = true;
bool skipGraphicsUpdate = false;
InProcessPhysicsClientExistingExampleBrowser* cl = new InProcessPhysicsClientExistingExampleBrowser(guiHelper, useInprocessMemory, skipGraphicsUpdate);
InProcessPhysicsClientExistingExampleBrowser* cl = new InProcessPhysicsClientExistingExampleBrowser(guiHelper, useInprocessMemory, skipGraphicsUpdate, false);
cl->connect();
return (b3PhysicsClientHandle)cl;
@@ -277,7 +284,7 @@ B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingEx
}
bool useInprocessMemory = false;
bool skipGraphicsUpdate = true;
InProcessPhysicsClientExistingExampleBrowser* cl = new InProcessPhysicsClientExistingExampleBrowser(guiHelper, useInprocessMemory, skipGraphicsUpdate);
InProcessPhysicsClientExistingExampleBrowser* cl = new InProcessPhysicsClientExistingExampleBrowser(guiHelper, useInprocessMemory, skipGraphicsUpdate, false);
cl->setSharedMemoryKey(sharedMemoryKey + 1);
cl->connect();
@@ -290,13 +297,15 @@ B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingEx
{
gSharedMemoryKey = sharedMemoryKey;
GUIHelperInterface* guiHelper = (GUIHelperInterface*)guiHelperPtr;
bool ownsGuiHelper = false;
if (!guiHelper)
{
guiHelper = new RemoteGUIHelper();
ownsGuiHelper = true;
}
bool useInprocessMemory = false;
bool skipGraphicsUpdate = false;
InProcessPhysicsClientExistingExampleBrowser* cl = new InProcessPhysicsClientExistingExampleBrowser(guiHelper, useInprocessMemory, skipGraphicsUpdate);
InProcessPhysicsClientExistingExampleBrowser* cl = new InProcessPhysicsClientExistingExampleBrowser(guiHelper, useInprocessMemory, skipGraphicsUpdate, ownsGuiHelper);
cl->setSharedMemoryKey(sharedMemoryKey + 1);
cl->connect();
@@ -305,6 +314,25 @@ B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingEx
return (b3PhysicsClientHandle)cl;
}
#include "RemoteGuiHelperTCP.h"
B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnectTCP(const char* hostName, int port)
{
bool ownsGuiHelper = true;
GUIHelperInterface* guiHelper = new RemoteGUIHelperTCP(hostName, port);
bool useInprocessMemory = true;
bool skipGraphicsUpdate = false;
InProcessPhysicsClientExistingExampleBrowser* cl = new InProcessPhysicsClientExistingExampleBrowser(guiHelper, useInprocessMemory, skipGraphicsUpdate, ownsGuiHelper);
//cl->setSharedMemoryKey(sharedMemoryKey + 1);
cl->connect();
//backward compatiblity
gSharedMemoryKey = SHARED_MEMORY_KEY;
return (b3PhysicsClientHandle)cl;
}
//backward compatiblity
B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect2(void* guiHelperPtr)