Add preliminary GRPC server for PyBullet and BulletRobotics.
Will add GRPC client and PyBullet GRPC server plugin. Will cover most/all SharedMemoryCommand/SharedMemoryStatus messages. Run the server, then test using the pybullet_client.py
This commit is contained in:
@@ -3008,8 +3008,10 @@ 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, int flags, btScalar globalScaling)
|
||||
bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes, int orgFlags, btScalar globalScaling)
|
||||
{
|
||||
//clear the LOAD_SDF_FILE=1 bit, which is reserved for internal use of loadSDF command.
|
||||
int flags = orgFlags & ~1;
|
||||
m_data->m_sdfRecentLoadedBodies.clear();
|
||||
*bodyUniqueIdPtr = -1;
|
||||
|
||||
|
||||
Reference in New Issue
Block a user