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:
erwincoumans
2018-08-29 21:12:13 -07:00
parent 65175425b0
commit 4f7dfc2069
18 changed files with 6556 additions and 29 deletions

View File

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