pybullet, more robust multi-server connections
Windows shared memory: allow to use custom key. Improve GUI performance on Windows, submit letters in text as a batch (fewer draw-calls) quadruped.py: first try to connect to SHARED_MEMORY, if it fails (<0) use GUI increase Chrome about://tracing json export capacity (press 'p' in Example Browser) UDP physics server: add --port and --sharedMemoryKey command-line arguments PhysicsServerExample: add --sharedMemoryKey command-line option (for VR example too) ExampleBrowser: sleep a few milliseconds if rendering is too fast, use --minUpdateTimeMicroSecs=0 to disable
This commit is contained in:
@@ -1044,6 +1044,7 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe
|
||||
bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVector3& pos, const btQuaternion& orn,
|
||||
bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes)
|
||||
{
|
||||
BT_PROFILE("loadURDF");
|
||||
btAssert(m_data->m_dynamicsWorld);
|
||||
if (!m_data->m_dynamicsWorld)
|
||||
{
|
||||
|
||||
Reference in New Issue
Block a user