allow pybullet to connect to GRPC server. (need to use flag --enable_grpc in premake build system)
add grpcPlugin, it can work in GUI, SHARED_MEMORY_SERVER, DIRECT and other modes.
example script to start server from pybullet:
import pybullet as p
p.connect(p.GUI)
#if statically linked plugin
id = p.loadPlugin("grpcPlugin")
#dynamics loading the plugin
#id = p.loadPlugin("E:/develop/bullet3/bin/pybullet_grpcPlugin_vs2010_x64_debug.dll", postFix="_grpcPlugin")
#start the GRPC server at hostname, port
if (id>=0):
p.executePluginCommand(id, "localhost:1234")
Only in DIRECT mode, since there is no 'ping' you need to call to handle RCPs:
numRPC = 10
while (1):
p.executePluginCommand(id, intArgs=[numRPC])
This commit is contained in:
@@ -23,6 +23,9 @@
|
|||||||
act = _ACTION
|
act = _ACTION
|
||||||
end
|
end
|
||||||
|
|
||||||
|
projectRootDir = os.getcwd() .. "/../"
|
||||||
|
print("Project root directory: " .. projectRootDir);
|
||||||
|
|
||||||
newoption {
|
newoption {
|
||||||
trigger = "ios",
|
trigger = "ios",
|
||||||
description = "Enable iOS target (requires xcode4)"
|
description = "Enable iOS target (requires xcode4)"
|
||||||
@@ -79,19 +82,23 @@
|
|||||||
|
|
||||||
if os.is("Linux") then
|
if os.is("Linux") then
|
||||||
default_grpc_include_dir = "usr/local/include/GRPC"
|
default_grpc_include_dir = "usr/local/include/GRPC"
|
||||||
default_grpc_lib_dir = "/usr/local/lib/"
|
default_grpc_lib_dir = "/usr/local/lib"
|
||||||
|
default_protobuf_include_dir = "/usr/local/include/protobuf"
|
||||||
|
default_protobuf_lib_dir = "/usr/local/lib"
|
||||||
end
|
end
|
||||||
|
|
||||||
if os.is("macosx") then
|
if os.is("macosx") then
|
||||||
default_grpc_include_dir = "/usr/local/Cellar/grpc/1.14.1/include"
|
default_grpc_include_dir = "/usr/local/Cellar/grpc/1.14.1/include"
|
||||||
default_grpc_lib_dir = "/usr/local/Cellar/grpc/1.14.1/lib"
|
default_grpc_lib_dir = "/usr/local/Cellar/grpc/1.14.1/lib"
|
||||||
default_protobuf_include_dir = "/usr/local/Cellar/protobuf/3.6.0/include/"
|
default_protobuf_include_dir = "/usr/local/Cellar/protobuf/3.6.0/include"
|
||||||
default_protobuf_lib_dir = "/usr/local/Cellar/protobuf/3.6.0/lib"
|
default_protobuf_lib_dir = "/usr/local/Cellar/protobuf/3.6.0/lib"
|
||||||
end
|
end
|
||||||
|
|
||||||
if os.is("Windows") then
|
if os.is("Windows") then
|
||||||
default_grpc_include_dir = "c:/grpc/include"
|
default_grpc_include_dir = projectRootDir .. "examples/ThirdPartyLibs/grpc/include"
|
||||||
default_grpc_lib_dir = "c:/grpc/lib"
|
default_grpc_lib_dir = projectRootDir .. "examples/ThirdPartyLibs/grpc/lib"
|
||||||
|
default_protobuf_include_dir =projectRootDir .. "examples/ThirdPartyLibs/grpc/include"
|
||||||
|
default_protobuf_lib_dir = projectRootDir .. "examples/ThirdPartyLibs/grpc/lib"
|
||||||
end
|
end
|
||||||
|
|
||||||
newoption
|
newoption
|
||||||
@@ -124,27 +131,80 @@
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
if not _OPTIONS["grpc_lib_dir"] then
|
||||||
|
_OPTIONS["grpc_lib_dir"] = default_grpc_lib_dir
|
||||||
|
end
|
||||||
|
if not _OPTIONS["grpc_include_dir"] then
|
||||||
|
_OPTIONS["grpc_include_dir"] = default_grpc_include_dir
|
||||||
|
end
|
||||||
|
if not _OPTIONS["protobuf_include_dir"] then
|
||||||
|
_OPTIONS["protobuf_include_dir"] = default_protobuf_include_dir
|
||||||
|
end
|
||||||
|
|
||||||
|
if not _OPTIONS["protobuf_lib_dir"] then
|
||||||
|
_OPTIONS["protobuf_lib_dir"] = default_protobuf_lib_dir
|
||||||
|
end
|
||||||
|
|
||||||
|
|
||||||
if _OPTIONS["enable_grpc"] then
|
if _OPTIONS["enable_grpc"] then
|
||||||
function initGRPC()
|
function initGRPC()
|
||||||
|
|
||||||
|
|
||||||
|
print "BT_ENABLE_GRPC"
|
||||||
|
|
||||||
|
print("grpc_include_dir=")
|
||||||
|
print(_OPTIONS["grpc_include_dir"])
|
||||||
|
print("grpc_lib_dir=")
|
||||||
|
print(_OPTIONS["grpc_lib_dir"])
|
||||||
|
print("protobuf_include_dir=")
|
||||||
|
print(_OPTIONS["protobuf_include_dir"])
|
||||||
|
print("protobuf_lib_dir=")
|
||||||
|
print(_OPTIONS["protobuf_lib_dir"])
|
||||||
|
|
||||||
|
defines {"BT_ENABLE_GRPC"}
|
||||||
|
|
||||||
|
if os.is("macosx") then
|
||||||
buildoptions { "-std=c++11" }
|
buildoptions { "-std=c++11" }
|
||||||
|
links{ "dl"}
|
||||||
|
end
|
||||||
|
|
||||||
defines {"BT_ENABLE_GRPC"}
|
if os.is("Linux") then
|
||||||
|
buildoptions { "-std=c++11" }
|
||||||
|
links{ "dl"}
|
||||||
|
end
|
||||||
|
|
||||||
includedirs {
|
if os.is("Windows") then
|
||||||
_OPTIONS["grpc_include_dir"], _OPTIONS["protobuf_include_dir"],
|
defines {"_WIN32_WINNT=0x0600"}
|
||||||
}
|
links{ "zlibstatic","ssl","crypto"}
|
||||||
|
end
|
||||||
|
|
||||||
libdirs {
|
includedirs {
|
||||||
_OPTIONS["grpc_lib_dir"], _OPTIONS["protobuf_lib_dir"],
|
projectRootDir .. "examples/SharedMemory", _OPTIONS["grpc_include_dir"], _OPTIONS["protobuf_include_dir"],
|
||||||
}
|
}
|
||||||
links { "grpc","grpc++", "grpc++_reflection", "gpr", "protobuf", "dl"}
|
|
||||||
files { projectRootDir .. "examples/SharedMemory/grpc/ConvertGRPCBullet.cpp",
|
if os.is("Windows") then
|
||||||
projectRootDir .. "examples/SharedMemory/grpc/ConvertGRPCBullet.h",
|
configuration {"x64", "debug"}
|
||||||
projectRootDir .. "examples/SharedMemory/grpc/pybullet.grpc.pb.cpp",
|
libdirs {_OPTIONS["grpc_lib_dir"] .. "/win64_debug" , _OPTIONS["protobuf_lib_dir"] .. "win64_debug",}
|
||||||
projectRootDir .. "examples/SharedMemory/grpc/pybullet.grpc.pb.h",
|
configuration {"x86", "debug"}
|
||||||
projectRootDir .. "examples/SharedMemory/grpc/pybullet.pb.cpp",
|
libdirs {_OPTIONS["grpc_lib_dir"] .. "/win32_debug" , _OPTIONS["protobuf_lib_dir"] .. "win32_debug",}
|
||||||
projectRootDir .. "examples/SharedMemory/grpc/pybullet.pb.h", }
|
configuration {"x64", "release"}
|
||||||
end
|
libdirs {_OPTIONS["grpc_lib_dir"] .. "/win64_release", _OPTIONS["protobuf_lib_dir"] .. "win64_release",}
|
||||||
|
configuration {"x86", "release"}
|
||||||
|
libdirs {_OPTIONS["grpc_lib_dir"] .. "/win32_release" , _OPTIONS["protobuf_lib_dir"] .. "win32_release",}
|
||||||
|
configuration{}
|
||||||
|
|
||||||
|
else
|
||||||
|
libdirs {_OPTIONS["grpc_lib_dir"], _OPTIONS["protobuf_lib_dir"],}
|
||||||
|
end
|
||||||
|
|
||||||
|
links { "grpc","grpc++", "grpc++_reflection", "gpr", "protobuf"}
|
||||||
|
files { projectRootDir .. "examples/SharedMemory/grpc/ConvertGRPCBullet.cpp",
|
||||||
|
projectRootDir .. "examples/SharedMemory/grpc/ConvertGRPCBullet.h",
|
||||||
|
projectRootDir .. "examples/SharedMemory/grpc/pybullet.grpc.pb.cpp",
|
||||||
|
projectRootDir .. "examples/SharedMemory/grpc/pybullet.grpc.pb.h",
|
||||||
|
projectRootDir .. "examples/SharedMemory/grpc/pybullet.pb.cpp",
|
||||||
|
projectRootDir .. "examples/SharedMemory/grpc/pybullet.pb.h", }
|
||||||
|
end
|
||||||
|
|
||||||
end
|
end
|
||||||
|
|
||||||
@@ -337,8 +397,7 @@ end
|
|||||||
targetdir( _OPTIONS["targetdir"] or "../bin" )
|
targetdir( _OPTIONS["targetdir"] or "../bin" )
|
||||||
location("./" .. act .. postfix)
|
location("./" .. act .. postfix)
|
||||||
|
|
||||||
projectRootDir = os.getcwd() .. "/../"
|
|
||||||
print("Project root directory: " .. projectRootDir);
|
|
||||||
|
|
||||||
if not _OPTIONS["python_include_dir"] then
|
if not _OPTIONS["python_include_dir"] then
|
||||||
_OPTIONS["python_include_dir"] = default_python_include_dir
|
_OPTIONS["python_include_dir"] = default_python_include_dir
|
||||||
|
|||||||
@@ -6,7 +6,20 @@ project "App_BulletExampleBrowser"
|
|||||||
|
|
||||||
if os.is("Linux") then
|
if os.is("Linux") then
|
||||||
buildoptions{"-fPIC"}
|
buildoptions{"-fPIC"}
|
||||||
end
|
end
|
||||||
|
|
||||||
|
if _OPTIONS["enable_grpc"] then
|
||||||
|
initGRPC()
|
||||||
|
defines{"ENABLE_STATIC_GRPC_PLUGIN"}
|
||||||
|
files {
|
||||||
|
"../../examples/SharedMemory/PhysicsClientGRPC.cpp",
|
||||||
|
"../../examples/SharedMemory/PhysicsClientGRPC.h",
|
||||||
|
"../../examples/SharedMemory/PhysicsClientGRPC_C_API.cpp",
|
||||||
|
"../../examples/SharedMemory/PhysicsClientGRPC_C_API.h",
|
||||||
|
"../../examples/SharedMemory/plugins/grpcPlugin/grpcPlugin.cpp",
|
||||||
|
|
||||||
|
}
|
||||||
|
end
|
||||||
|
|
||||||
hasCL = findOpenCL("clew")
|
hasCL = findOpenCL("clew")
|
||||||
|
|
||||||
|
|||||||
@@ -2397,9 +2397,9 @@ B3_SHARED_API void b3CustomCommandExecutePluginCommand(b3SharedMemoryCommandHand
|
|||||||
command->m_customCommandArgs.m_arguments.m_numFloats = 0;
|
command->m_customCommandArgs.m_arguments.m_numFloats = 0;
|
||||||
command->m_customCommandArgs.m_arguments.m_text[0] = 0;
|
command->m_customCommandArgs.m_arguments.m_text[0] = 0;
|
||||||
|
|
||||||
int len = strlen(textArguments);
|
int len = textArguments ? strlen(textArguments) : 0;
|
||||||
|
|
||||||
if (len<MAX_FILENAME_LENGTH)
|
if (len && len<MAX_FILENAME_LENGTH)
|
||||||
{
|
{
|
||||||
strcpy(command->m_customCommandArgs.m_arguments.m_text, textArguments);
|
strcpy(command->m_customCommandArgs.m_arguments.m_text, textArguments);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -155,6 +155,11 @@ bool GRPCNetworkedPhysicsProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
|
|
||||||
//convert grpc status to Bullet status
|
//convert grpc status to Bullet status
|
||||||
bool convertedOk = convertGRPCToStatus(status, serverStatusOut, bufferServerToClient, bufferSizeInBytes);
|
bool convertedOk = convertGRPCToStatus(status, serverStatusOut, bufferServerToClient, bufferSizeInBytes);
|
||||||
|
if (!convertedOk)
|
||||||
|
{
|
||||||
|
disconnect();
|
||||||
|
|
||||||
|
}
|
||||||
return convertedOk;
|
return convertedOk;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -60,6 +60,9 @@ public:
|
|||||||
|
|
||||||
virtual const btQuaternion& getVRTeleportOrientation() const=0;
|
virtual const btQuaternion& getVRTeleportOrientation() const=0;
|
||||||
virtual void setVRTeleportOrientation(const btQuaternion& vrReleportOrn)=0;
|
virtual void setVRTeleportOrientation(const btQuaternion& vrReleportOrn)=0;
|
||||||
|
|
||||||
|
virtual void processClientCommands() = 0;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif //PHYSICS_COMMAND_PROCESSOR_INTERFACE_H
|
#endif //PHYSICS_COMMAND_PROCESSOR_INTERFACE_H
|
||||||
|
|||||||
@@ -54,6 +54,11 @@
|
|||||||
#include "plugins/collisionFilterPlugin/collisionFilterPlugin.h"
|
#include "plugins/collisionFilterPlugin/collisionFilterPlugin.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef ENABLE_STATIC_GRPC_PLUGIN
|
||||||
|
#include "plugins/grpcPlugin/grpcPlugin.h"
|
||||||
|
#endif //ENABLE_STATIC_GRPC_PLUGIN
|
||||||
|
|
||||||
#ifndef SKIP_STATIC_PD_CONTROL_PLUGIN
|
#ifndef SKIP_STATIC_PD_CONTROL_PLUGIN
|
||||||
#include "plugins/pdControlPlugin/pdControlPlugin.h"
|
#include "plugins/pdControlPlugin/pdControlPlugin.h"
|
||||||
#endif //SKIP_STATIC_PD_CONTROL_PLUGIN
|
#endif //SKIP_STATIC_PD_CONTROL_PLUGIN
|
||||||
@@ -1635,6 +1640,7 @@ struct PhysicsServerCommandProcessorInternalData
|
|||||||
bool m_prevCanSleep;
|
bool m_prevCanSleep;
|
||||||
int m_pdControlPlugin;
|
int m_pdControlPlugin;
|
||||||
int m_collisionFilterPlugin;
|
int m_collisionFilterPlugin;
|
||||||
|
int m_grpcPlugin;
|
||||||
|
|
||||||
#ifdef B3_ENABLE_TINY_AUDIO
|
#ifdef B3_ENABLE_TINY_AUDIO
|
||||||
b3SoundEngine m_soundEngine;
|
b3SoundEngine m_soundEngine;
|
||||||
@@ -1675,29 +1681,37 @@ struct PhysicsServerCommandProcessorInternalData
|
|||||||
m_pickingMultiBodyPoint2Point(0),
|
m_pickingMultiBodyPoint2Point(0),
|
||||||
m_pdControlPlugin(-1),
|
m_pdControlPlugin(-1),
|
||||||
m_collisionFilterPlugin(-1),
|
m_collisionFilterPlugin(-1),
|
||||||
|
m_grpcPlugin(-1),
|
||||||
m_threadPool(0)
|
m_threadPool(0)
|
||||||
{
|
{
|
||||||
|
|
||||||
{
|
{
|
||||||
//register static plugins:
|
//register static plugins:
|
||||||
#ifdef STATIC_LINK_VR_PLUGIN
|
#ifdef STATIC_LINK_VR_PLUGIN
|
||||||
m_pluginManager.registerStaticLinkedPlugin("vrSyncPlugin", initPlugin_vrSyncPlugin, exitPlugin_vrSyncPlugin, executePluginCommand_vrSyncPlugin, preTickPluginCallback_vrSyncPlugin, 0, 0);
|
m_pluginManager.registerStaticLinkedPlugin("vrSyncPlugin", initPlugin_vrSyncPlugin, exitPlugin_vrSyncPlugin, executePluginCommand_vrSyncPlugin, preTickPluginCallback_vrSyncPlugin, 0, 0,0);
|
||||||
#endif //STATIC_LINK_VR_PLUGIN
|
#endif //STATIC_LINK_VR_PLUGIN
|
||||||
|
|
||||||
#ifndef SKIP_STATIC_PD_CONTROL_PLUGIN
|
#ifndef SKIP_STATIC_PD_CONTROL_PLUGIN
|
||||||
{
|
{
|
||||||
m_pdControlPlugin = m_pluginManager.registerStaticLinkedPlugin("pdControlPlugin", initPlugin_pdControlPlugin, exitPlugin_pdControlPlugin, executePluginCommand_pdControlPlugin, preTickPluginCallback_pdControlPlugin, 0, 0);
|
m_pdControlPlugin = m_pluginManager.registerStaticLinkedPlugin("pdControlPlugin", initPlugin_pdControlPlugin, exitPlugin_pdControlPlugin, executePluginCommand_pdControlPlugin, preTickPluginCallback_pdControlPlugin, 0, 0,0);
|
||||||
}
|
}
|
||||||
#endif //SKIP_STATIC_PD_CONTROL_PLUGIN
|
#endif //SKIP_STATIC_PD_CONTROL_PLUGIN
|
||||||
|
|
||||||
#ifndef SKIP_COLLISION_FILTER_PLUGIN
|
#ifndef SKIP_COLLISION_FILTER_PLUGIN
|
||||||
{
|
{
|
||||||
m_collisionFilterPlugin = m_pluginManager.registerStaticLinkedPlugin("collisionFilterPlugin", initPlugin_collisionFilterPlugin, exitPlugin_collisionFilterPlugin, executePluginCommand_collisionFilterPlugin, 0,0,0);
|
m_collisionFilterPlugin = m_pluginManager.registerStaticLinkedPlugin("collisionFilterPlugin", initPlugin_collisionFilterPlugin, exitPlugin_collisionFilterPlugin, executePluginCommand_collisionFilterPlugin, 0,0,0,0);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef ENABLE_STATIC_GRPC_PLUGIN
|
||||||
|
{
|
||||||
|
m_grpcPlugin = m_pluginManager.registerStaticLinkedPlugin("grpcPlugin", initPlugin_grpcPlugin, exitPlugin_grpcPlugin, executePluginCommand_grpcPlugin, 0, 0, 0,processClientCommands_grpcPlugin);
|
||||||
|
}
|
||||||
|
#endif //ENABLE_STATIC_GRPC_PLUGIN
|
||||||
|
|
||||||
|
|
||||||
#ifndef SKIP_STATIC_TINYRENDERER_PLUGIN
|
#ifndef SKIP_STATIC_TINYRENDERER_PLUGIN
|
||||||
int renderPluginId = m_pluginManager.registerStaticLinkedPlugin("tinyRendererPlugin", initPlugin_tinyRendererPlugin, exitPlugin_tinyRendererPlugin, executePluginCommand_tinyRendererPlugin,0,0,getRenderInterface_tinyRendererPlugin);
|
int renderPluginId = m_pluginManager.registerStaticLinkedPlugin("tinyRendererPlugin", initPlugin_tinyRendererPlugin, exitPlugin_tinyRendererPlugin, executePluginCommand_tinyRendererPlugin,0,0,getRenderInterface_tinyRendererPlugin,0);
|
||||||
m_pluginManager.selectPluginRenderer(renderPluginId);
|
m_pluginManager.selectPluginRenderer(renderPluginId);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
@@ -1799,8 +1813,8 @@ PhysicsServerCommandProcessor::~PhysicsServerCommandProcessor()
|
|||||||
void preTickCallback(btDynamicsWorld *world, btScalar timeStep)
|
void preTickCallback(btDynamicsWorld *world, btScalar timeStep)
|
||||||
{
|
{
|
||||||
PhysicsServerCommandProcessor* proc = (PhysicsServerCommandProcessor*) world->getWorldUserInfo();
|
PhysicsServerCommandProcessor* proc = (PhysicsServerCommandProcessor*) world->getWorldUserInfo();
|
||||||
bool isPreTick = true;
|
|
||||||
proc->tickPlugins(timeStep, isPreTick);
|
proc->tickPlugins(timeStep, true);
|
||||||
}
|
}
|
||||||
|
|
||||||
void logCallback(btDynamicsWorld *world, btScalar timeStep)
|
void logCallback(btDynamicsWorld *world, btScalar timeStep)
|
||||||
@@ -1810,8 +1824,7 @@ void logCallback(btDynamicsWorld *world, btScalar timeStep)
|
|||||||
proc->processCollisionForces(timeStep);
|
proc->processCollisionForces(timeStep);
|
||||||
proc->logObjectStates(timeStep);
|
proc->logObjectStates(timeStep);
|
||||||
|
|
||||||
bool isPreTick = false;
|
proc->tickPlugins(timeStep, false);
|
||||||
proc->tickPlugins(timeStep, isPreTick);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool MyContactAddedCallback(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap,int partId0,int index0,const btCollisionObjectWrapper* colObj1Wrap,int partId1,int index1)
|
bool MyContactAddedCallback(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap,int partId0,int index0,const btCollisionObjectWrapper* colObj1Wrap,int partId1,int index1)
|
||||||
@@ -1920,13 +1933,21 @@ void PhysicsServerCommandProcessor::processCollisionForces(btScalar timeStep)
|
|||||||
#endif//B3_ENABLE_TINY_AUDIO
|
#endif//B3_ENABLE_TINY_AUDIO
|
||||||
}
|
}
|
||||||
|
|
||||||
void PhysicsServerCommandProcessor::reportNotifications() {
|
void PhysicsServerCommandProcessor::processClientCommands()
|
||||||
|
{
|
||||||
|
m_data->m_pluginManager.tickPlugins(0, B3_PROCESS_CLIENT_COMMANDS_TICK);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void PhysicsServerCommandProcessor::reportNotifications()
|
||||||
|
{
|
||||||
m_data->m_pluginManager.reportNotifications();
|
m_data->m_pluginManager.reportNotifications();
|
||||||
}
|
}
|
||||||
|
|
||||||
void PhysicsServerCommandProcessor::tickPlugins(btScalar timeStep, bool isPreTick)
|
void PhysicsServerCommandProcessor::tickPlugins(btScalar timeStep, bool isPreTick)
|
||||||
{
|
{
|
||||||
m_data->m_pluginManager.tickPlugins(timeStep, isPreTick);
|
b3PluginManagerTickMode tickMode = isPreTick ? B3_PRE_TICK_MODE : B3_POST_TICK_MODE;
|
||||||
|
m_data->m_pluginManager.tickPlugins(timeStep, tickMode);
|
||||||
if (!isPreTick)
|
if (!isPreTick)
|
||||||
{
|
{
|
||||||
//clear events after each postTick, so we don't receive events multiple ticks
|
//clear events after each postTick, so we don't receive events multiple ticks
|
||||||
@@ -9901,6 +9922,7 @@ bool PhysicsServerCommandProcessor::processSaveBulletCommand(const struct Shared
|
|||||||
return hasStatus;
|
return hasStatus;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes )
|
bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes )
|
||||||
{
|
{
|
||||||
// BT_PROFILE("processCommand");
|
// BT_PROFILE("processCommand");
|
||||||
|
|||||||
@@ -128,8 +128,6 @@ public:
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
virtual bool processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
virtual bool processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
|
||||||
|
|
||||||
virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
|
virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
|
||||||
@@ -156,6 +154,7 @@ public:
|
|||||||
|
|
||||||
//logging of object states (position etc)
|
//logging of object states (position etc)
|
||||||
virtual void reportNotifications();
|
virtual void reportNotifications();
|
||||||
|
virtual void processClientCommands();
|
||||||
void tickPlugins(btScalar timeStep, bool isPreTick);
|
void tickPlugins(btScalar timeStep, bool isPreTick);
|
||||||
void logObjectStates(btScalar timeStep);
|
void logObjectStates(btScalar timeStep);
|
||||||
void processCollisionForces(btScalar timeStep);
|
void processCollisionForces(btScalar timeStep);
|
||||||
|
|||||||
@@ -249,6 +249,8 @@ void PhysicsServerSharedMemory::reportNotifications()
|
|||||||
|
|
||||||
void PhysicsServerSharedMemory::processClientCommands()
|
void PhysicsServerSharedMemory::processClientCommands()
|
||||||
{
|
{
|
||||||
|
m_data->m_commandProcessor->processClientCommands();
|
||||||
|
|
||||||
for (int block = 0;block<MAX_SHARED_MEMORY_BLOCKS;block++)
|
for (int block = 0;block<MAX_SHARED_MEMORY_BLOCKS;block++)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
|||||||
@@ -43,6 +43,7 @@ struct b3Plugin
|
|||||||
PFN_TICK m_preTickFunc;
|
PFN_TICK m_preTickFunc;
|
||||||
PFN_TICK m_postTickFunc;
|
PFN_TICK m_postTickFunc;
|
||||||
PFN_TICK m_processNotificationsFunc;
|
PFN_TICK m_processNotificationsFunc;
|
||||||
|
PFN_TICK m_processClientCommandsFunc;
|
||||||
|
|
||||||
PFN_GET_RENDER_INTERFACE m_getRendererFunc;
|
PFN_GET_RENDER_INTERFACE m_getRendererFunc;
|
||||||
|
|
||||||
@@ -58,6 +59,7 @@ struct b3Plugin
|
|||||||
m_preTickFunc(0),
|
m_preTickFunc(0),
|
||||||
m_postTickFunc(0),
|
m_postTickFunc(0),
|
||||||
m_processNotificationsFunc(0),
|
m_processNotificationsFunc(0),
|
||||||
|
m_processClientCommandsFunc(0),
|
||||||
m_getRendererFunc(0),
|
m_getRendererFunc(0),
|
||||||
m_userPointer(0)
|
m_userPointer(0)
|
||||||
{
|
{
|
||||||
@@ -74,8 +76,10 @@ struct b3Plugin
|
|||||||
m_executeCommandFunc = 0;
|
m_executeCommandFunc = 0;
|
||||||
m_preTickFunc = 0;
|
m_preTickFunc = 0;
|
||||||
m_postTickFunc = 0;
|
m_postTickFunc = 0;
|
||||||
m_userPointer = 0;
|
m_processNotificationsFunc = 0;
|
||||||
|
m_processClientCommandsFunc = 0;
|
||||||
m_getRendererFunc = 0;
|
m_getRendererFunc = 0;
|
||||||
|
m_userPointer = 0;
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
@@ -86,6 +90,7 @@ struct b3PluginManagerInternalData
|
|||||||
b3ResizablePool<b3PluginHandle> m_plugins;
|
b3ResizablePool<b3PluginHandle> m_plugins;
|
||||||
b3HashMap<b3HashString, int> m_pluginMap;
|
b3HashMap<b3HashString, int> m_pluginMap;
|
||||||
PhysicsDirect* m_physicsDirect;
|
PhysicsDirect* m_physicsDirect;
|
||||||
|
PhysicsCommandProcessorInterface* m_rpcCommandProcessorInterface;
|
||||||
b3AlignedObjectArray<b3KeyboardEvent> m_keyEvents;
|
b3AlignedObjectArray<b3KeyboardEvent> m_keyEvents;
|
||||||
b3AlignedObjectArray<b3VRControllerEvent> m_vrEvents;
|
b3AlignedObjectArray<b3VRControllerEvent> m_vrEvents;
|
||||||
b3AlignedObjectArray<b3MouseEvent> m_mouseEvents;
|
b3AlignedObjectArray<b3MouseEvent> m_mouseEvents;
|
||||||
@@ -95,7 +100,7 @@ struct b3PluginManagerInternalData
|
|||||||
int m_numNotificationPlugins;
|
int m_numNotificationPlugins;
|
||||||
|
|
||||||
b3PluginManagerInternalData()
|
b3PluginManagerInternalData()
|
||||||
:m_activeNotificationsBufferIndex(0), m_activeRendererPluginUid(-1),
|
:m_rpcCommandProcessorInterface(0), m_activeNotificationsBufferIndex(0), m_activeRendererPluginUid(-1),
|
||||||
m_numNotificationPlugins(0)
|
m_numNotificationPlugins(0)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
@@ -104,6 +109,7 @@ struct b3PluginManagerInternalData
|
|||||||
b3PluginManager::b3PluginManager(class PhysicsCommandProcessorInterface* physSdk)
|
b3PluginManager::b3PluginManager(class PhysicsCommandProcessorInterface* physSdk)
|
||||||
{
|
{
|
||||||
m_data = new b3PluginManagerInternalData;
|
m_data = new b3PluginManagerInternalData;
|
||||||
|
m_data->m_rpcCommandProcessorInterface = physSdk;
|
||||||
m_data->m_physicsDirect = new PhysicsDirect(physSdk,false);
|
m_data->m_physicsDirect = new PhysicsDirect(physSdk,false);
|
||||||
|
|
||||||
}
|
}
|
||||||
@@ -184,6 +190,7 @@ int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr)
|
|||||||
std::string preTickPluginCallbackStr = std::string("preTickPluginCallback") + postFix;
|
std::string preTickPluginCallbackStr = std::string("preTickPluginCallback") + postFix;
|
||||||
std::string postTickPluginCallback = std::string("postTickPluginCallback") + postFix;
|
std::string postTickPluginCallback = std::string("postTickPluginCallback") + postFix;
|
||||||
std::string processNotificationsStr = std::string("processNotifications") + postFix;
|
std::string processNotificationsStr = std::string("processNotifications") + postFix;
|
||||||
|
std::string processClientCommandsStr = std::string("processClientCommands") + postFix;
|
||||||
std::string getRendererStr = std::string("getRenderInterface") + postFix;
|
std::string getRendererStr = std::string("getRenderInterface") + postFix;
|
||||||
|
|
||||||
plugin->m_initFunc = (PFN_INIT)B3_DYNLIB_IMPORT(pluginHandle, initStr.c_str());
|
plugin->m_initFunc = (PFN_INIT)B3_DYNLIB_IMPORT(pluginHandle, initStr.c_str());
|
||||||
@@ -192,10 +199,12 @@ int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr)
|
|||||||
plugin->m_preTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, preTickPluginCallbackStr.c_str());
|
plugin->m_preTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, preTickPluginCallbackStr.c_str());
|
||||||
plugin->m_postTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, postTickPluginCallback.c_str());
|
plugin->m_postTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, postTickPluginCallback.c_str());
|
||||||
plugin->m_processNotificationsFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, processNotificationsStr.c_str());
|
plugin->m_processNotificationsFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, processNotificationsStr.c_str());
|
||||||
|
|
||||||
if (plugin->m_processNotificationsFunc)
|
if (plugin->m_processNotificationsFunc)
|
||||||
{
|
{
|
||||||
m_data->m_numNotificationPlugins++;
|
m_data->m_numNotificationPlugins++;
|
||||||
}
|
}
|
||||||
|
plugin->m_processClientCommandsFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, processClientCommandsStr.c_str());
|
||||||
|
|
||||||
plugin->m_getRendererFunc = (PFN_GET_RENDER_INTERFACE)B3_DYNLIB_IMPORT(pluginHandle, getRendererStr.c_str());
|
plugin->m_getRendererFunc = (PFN_GET_RENDER_INTERFACE)B3_DYNLIB_IMPORT(pluginHandle, getRendererStr.c_str());
|
||||||
|
|
||||||
@@ -206,6 +215,7 @@ int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr)
|
|||||||
b3PluginContext context;
|
b3PluginContext context;
|
||||||
context.m_userPointer = plugin->m_userPointer;
|
context.m_userPointer = plugin->m_userPointer;
|
||||||
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
||||||
|
context.m_rpcCommandProcessorInterface = m_data->m_rpcCommandProcessorInterface;
|
||||||
int version = plugin->m_initFunc(&context);
|
int version = plugin->m_initFunc(&context);
|
||||||
//keep the user pointer persistent
|
//keep the user pointer persistent
|
||||||
plugin->m_userPointer = context.m_userPointer;
|
plugin->m_userPointer = context.m_userPointer;
|
||||||
@@ -276,7 +286,9 @@ void b3PluginManager::unloadPlugin(int pluginUniqueId)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void b3PluginManager::tickPlugins(double timeStep, bool isPreTick)
|
|
||||||
|
|
||||||
|
void b3PluginManager::tickPlugins(double timeStep, b3PluginManagerTickMode tickMode)
|
||||||
{
|
{
|
||||||
for (int i=0;i<m_data->m_pluginMap.size();i++)
|
for (int i=0;i<m_data->m_pluginMap.size();i++)
|
||||||
{
|
{
|
||||||
@@ -293,18 +305,44 @@ void b3PluginManager::tickPlugins(double timeStep, bool isPreTick)
|
|||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
PFN_TICK tick = isPreTick? plugin->m_preTickFunc : plugin->m_postTickFunc;
|
PFN_TICK tick = 0;
|
||||||
|
switch (tickMode)
|
||||||
|
{
|
||||||
|
case B3_PRE_TICK_MODE:
|
||||||
|
{
|
||||||
|
tick = plugin->m_preTickFunc;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case B3_POST_TICK_MODE:
|
||||||
|
{
|
||||||
|
tick = plugin->m_postTickFunc;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case B3_PROCESS_CLIENT_COMMANDS_TICK:
|
||||||
|
{
|
||||||
|
tick = plugin->m_processClientCommandsFunc;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
{
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (tick)
|
if (tick)
|
||||||
{
|
{
|
||||||
b3PluginContext context = {0};
|
b3PluginContext context = { 0 };
|
||||||
context.m_userPointer = plugin->m_userPointer;
|
context.m_userPointer = plugin->m_userPointer;
|
||||||
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
context.m_physClient = (b3PhysicsClientHandle)m_data->m_physicsDirect;
|
||||||
context.m_numMouseEvents = m_data->m_mouseEvents.size();
|
context.m_numMouseEvents = m_data->m_mouseEvents.size();
|
||||||
context.m_mouseEvents = m_data->m_mouseEvents.size() ? &m_data->m_mouseEvents[0] : 0;
|
context.m_mouseEvents = m_data->m_mouseEvents.size() ? &m_data->m_mouseEvents[0] : 0;
|
||||||
context.m_numKeyEvents = m_data->m_keyEvents.size();
|
context.m_numKeyEvents = m_data->m_keyEvents.size();
|
||||||
context.m_keyEvents = m_data->m_keyEvents.size() ? &m_data->m_keyEvents[0] : 0;
|
context.m_keyEvents = m_data->m_keyEvents.size() ? &m_data->m_keyEvents[0] : 0;
|
||||||
context.m_numVRControllerEvents = m_data->m_vrEvents.size();
|
context.m_numVRControllerEvents = m_data->m_vrEvents.size();
|
||||||
context.m_vrControllerEvents = m_data->m_vrEvents.size()? &m_data->m_vrEvents[0]:0;
|
context.m_vrControllerEvents = m_data->m_vrEvents.size() ? &m_data->m_vrEvents[0] : 0;
|
||||||
|
if (tickMode == B3_PROCESS_CLIENT_COMMANDS_TICK)
|
||||||
|
{
|
||||||
|
context.m_rpcCommandProcessorInterface = m_data->m_rpcCommandProcessorInterface;
|
||||||
|
}
|
||||||
int result = tick(&context);
|
int result = tick(&context);
|
||||||
plugin->m_userPointer = context.m_userPointer;
|
plugin->m_userPointer = context.m_userPointer;
|
||||||
}
|
}
|
||||||
@@ -359,7 +397,7 @@ int b3PluginManager::executePluginCommand(int pluginUniqueId, const b3PluginArgu
|
|||||||
b3PluginContext context = {0};
|
b3PluginContext context = {0};
|
||||||
context.m_userPointer = plugin->m_userPointer;
|
context.m_userPointer = plugin->m_userPointer;
|
||||||
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
||||||
|
context.m_rpcCommandProcessorInterface = m_data->m_rpcCommandProcessorInterface;
|
||||||
result = plugin->m_executeCommandFunc(&context, arguments);
|
result = plugin->m_executeCommandFunc(&context, arguments);
|
||||||
plugin->m_userPointer = context.m_userPointer;
|
plugin->m_userPointer = context.m_userPointer;
|
||||||
}
|
}
|
||||||
@@ -367,7 +405,7 @@ int b3PluginManager::executePluginCommand(int pluginUniqueId, const b3PluginArgu
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc, PFN_GET_RENDER_INTERFACE getRendererFunc)
|
int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc, PFN_GET_RENDER_INTERFACE getRendererFunc, PFN_TICK processClientCommandsFunc)
|
||||||
{
|
{
|
||||||
|
|
||||||
b3Plugin orgPlugin;
|
b3Plugin orgPlugin;
|
||||||
@@ -383,6 +421,7 @@ int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT
|
|||||||
pluginHandle->m_preTickFunc = preTickFunc;
|
pluginHandle->m_preTickFunc = preTickFunc;
|
||||||
pluginHandle->m_postTickFunc = postTickFunc;
|
pluginHandle->m_postTickFunc = postTickFunc;
|
||||||
pluginHandle->m_getRendererFunc = getRendererFunc;
|
pluginHandle->m_getRendererFunc = getRendererFunc;
|
||||||
|
pluginHandle->m_processClientCommandsFunc = processClientCommandsFunc;
|
||||||
pluginHandle->m_pluginHandle = 0;
|
pluginHandle->m_pluginHandle = 0;
|
||||||
pluginHandle->m_pluginPath = pluginPath;
|
pluginHandle->m_pluginPath = pluginPath;
|
||||||
pluginHandle->m_userPointer = 0;
|
pluginHandle->m_userPointer = 0;
|
||||||
@@ -399,7 +438,7 @@ int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT
|
|||||||
b3PluginContext context = {0};
|
b3PluginContext context = {0};
|
||||||
context.m_userPointer = 0;
|
context.m_userPointer = 0;
|
||||||
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
||||||
|
context.m_rpcCommandProcessorInterface = m_data->m_rpcCommandProcessorInterface;
|
||||||
int result = pluginHandle->m_initFunc(&context);
|
int result = pluginHandle->m_initFunc(&context);
|
||||||
pluginHandle->m_userPointer = context.m_userPointer;
|
pluginHandle->m_userPointer = context.m_userPointer;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -3,6 +3,13 @@
|
|||||||
|
|
||||||
#include "plugins/b3PluginAPI.h"
|
#include "plugins/b3PluginAPI.h"
|
||||||
|
|
||||||
|
enum b3PluginManagerTickMode
|
||||||
|
{
|
||||||
|
B3_PRE_TICK_MODE=1,
|
||||||
|
B3_POST_TICK_MODE,
|
||||||
|
B3_PROCESS_CLIENT_COMMANDS_TICK,
|
||||||
|
};
|
||||||
|
|
||||||
class b3PluginManager
|
class b3PluginManager
|
||||||
{
|
{
|
||||||
struct b3PluginManagerInternalData* m_data;
|
struct b3PluginManagerInternalData* m_data;
|
||||||
@@ -21,10 +28,9 @@ class b3PluginManager
|
|||||||
void addNotification(const struct b3Notification& notification);
|
void addNotification(const struct b3Notification& notification);
|
||||||
void reportNotifications();
|
void reportNotifications();
|
||||||
|
|
||||||
void tickPlugins(double timeStep, bool isPreTick);
|
void tickPlugins(double timeStep, b3PluginManagerTickMode tickMode);
|
||||||
|
|
||||||
int registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc, PFN_GET_RENDER_INTERFACE getRendererFunc);
|
|
||||||
|
|
||||||
|
int registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc, PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc, PFN_GET_RENDER_INTERFACE getRendererFunc, PFN_TICK processClientCommandsFunc);
|
||||||
void selectPluginRenderer(int pluginUniqueId);
|
void selectPluginRenderer(int pluginUniqueId);
|
||||||
UrdfRenderingInterface* getRenderInterface();
|
UrdfRenderingInterface* getRenderInterface();
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -5,7 +5,7 @@ project ("App_PhysicsServerSharedMemoryBridgeGRPC")
|
|||||||
|
|
||||||
kind "ConsoleApp"
|
kind "ConsoleApp"
|
||||||
|
|
||||||
includedirs {"../../ThirdPartyLibs/clsocket/src","../../../src",".."}
|
includedirs {"../../../src",".."}
|
||||||
|
|
||||||
initGRPC()
|
initGRPC()
|
||||||
|
|
||||||
|
|||||||
@@ -5,14 +5,14 @@
|
|||||||
#include "pybullet.pb.h"
|
#include "pybullet.pb.h"
|
||||||
#include "pybullet.grpc.pb.h"
|
#include "pybullet.grpc.pb.h"
|
||||||
|
|
||||||
#include <grpcpp/impl/codegen/async_stream.h>
|
#include <grpc++/impl/codegen/async_stream.h>
|
||||||
#include <grpcpp/impl/codegen/async_unary_call.h>
|
#include <grpc++/impl/codegen/async_unary_call.h>
|
||||||
#include <grpcpp/impl/codegen/channel_interface.h>
|
#include <grpc++/impl/codegen/channel_interface.h>
|
||||||
#include <grpcpp/impl/codegen/client_unary_call.h>
|
#include <grpc++/impl/codegen/client_unary_call.h>
|
||||||
#include <grpcpp/impl/codegen/method_handler_impl.h>
|
#include <grpc++/impl/codegen/method_handler_impl.h>
|
||||||
#include <grpcpp/impl/codegen/rpc_service_method.h>
|
#include <grpc++/impl/codegen/rpc_service_method.h>
|
||||||
#include <grpcpp/impl/codegen/service_type.h>
|
#include <grpc++/impl/codegen/service_type.h>
|
||||||
#include <grpcpp/impl/codegen/sync_stream.h>
|
#include <grpc++/impl/codegen/sync_stream.h>
|
||||||
namespace pybullet_grpc {
|
namespace pybullet_grpc {
|
||||||
|
|
||||||
static const char* PyBulletAPI_method_names[] = {
|
static const char* PyBulletAPI_method_names[] = {
|
||||||
@@ -20,32 +20,27 @@ static const char* PyBulletAPI_method_names[] = {
|
|||||||
};
|
};
|
||||||
|
|
||||||
std::unique_ptr< PyBulletAPI::Stub> PyBulletAPI::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) {
|
std::unique_ptr< PyBulletAPI::Stub> PyBulletAPI::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) {
|
||||||
(void)options;
|
|
||||||
std::unique_ptr< PyBulletAPI::Stub> stub(new PyBulletAPI::Stub(channel));
|
std::unique_ptr< PyBulletAPI::Stub> stub(new PyBulletAPI::Stub(channel));
|
||||||
return stub;
|
return stub;
|
||||||
}
|
}
|
||||||
|
|
||||||
PyBulletAPI::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel)
|
PyBulletAPI::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel)
|
||||||
: channel_(channel), rpcmethod_SubmitCommand_(PyBulletAPI_method_names[0], ::grpc::internal::RpcMethod::NORMAL_RPC, channel)
|
: channel_(channel), rpcmethod_SubmitCommand_(PyBulletAPI_method_names[0], ::grpc::RpcMethod::NORMAL_RPC, channel)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
::grpc::Status PyBulletAPI::Stub::SubmitCommand(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::pybullet_grpc::PyBulletStatus* response) {
|
::grpc::Status PyBulletAPI::Stub::SubmitCommand(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::pybullet_grpc::PyBulletStatus* response) {
|
||||||
return ::grpc::internal::BlockingUnaryCall(channel_.get(), rpcmethod_SubmitCommand_, context, request, response);
|
return ::grpc::BlockingUnaryCall(channel_.get(), rpcmethod_SubmitCommand_, context, request, response);
|
||||||
}
|
}
|
||||||
|
|
||||||
::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>* PyBulletAPI::Stub::AsyncSubmitCommandRaw(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) {
|
::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>* PyBulletAPI::Stub::AsyncSubmitCommandRaw(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) {
|
||||||
return ::grpc::internal::ClientAsyncResponseReaderFactory< ::pybullet_grpc::PyBulletStatus>::Create(channel_.get(), cq, rpcmethod_SubmitCommand_, context, request, true);
|
return new ::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>(channel_.get(), cq, rpcmethod_SubmitCommand_, context, request);
|
||||||
}
|
|
||||||
|
|
||||||
::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>* PyBulletAPI::Stub::PrepareAsyncSubmitCommandRaw(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) {
|
|
||||||
return ::grpc::internal::ClientAsyncResponseReaderFactory< ::pybullet_grpc::PyBulletStatus>::Create(channel_.get(), cq, rpcmethod_SubmitCommand_, context, request, false);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
PyBulletAPI::Service::Service() {
|
PyBulletAPI::Service::Service() {
|
||||||
AddMethod(new ::grpc::internal::RpcServiceMethod(
|
AddMethod(new ::grpc::RpcServiceMethod(
|
||||||
PyBulletAPI_method_names[0],
|
PyBulletAPI_method_names[0],
|
||||||
::grpc::internal::RpcMethod::NORMAL_RPC,
|
::grpc::RpcMethod::NORMAL_RPC,
|
||||||
new ::grpc::internal::RpcMethodHandler< PyBulletAPI::Service, ::pybullet_grpc::PyBulletCommand, ::pybullet_grpc::PyBulletStatus>(
|
new ::grpc::RpcMethodHandler< PyBulletAPI::Service, ::pybullet_grpc::PyBulletCommand, ::pybullet_grpc::PyBulletStatus>(
|
||||||
std::mem_fn(&PyBulletAPI::Service::SubmitCommand), this)));
|
std::mem_fn(&PyBulletAPI::Service::SubmitCommand), this)));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -6,20 +6,20 @@
|
|||||||
|
|
||||||
#include "pybullet.pb.h"
|
#include "pybullet.pb.h"
|
||||||
|
|
||||||
#include <grpcpp/impl/codegen/async_generic_service.h>
|
#include <grpc++/impl/codegen/async_stream.h>
|
||||||
#include <grpcpp/impl/codegen/async_stream.h>
|
#include <grpc++/impl/codegen/async_unary_call.h>
|
||||||
#include <grpcpp/impl/codegen/async_unary_call.h>
|
#include <grpc++/impl/codegen/method_handler_impl.h>
|
||||||
#include <grpcpp/impl/codegen/method_handler_impl.h>
|
#include <grpc++/impl/codegen/proto_utils.h>
|
||||||
#include <grpcpp/impl/codegen/proto_utils.h>
|
#include <grpc++/impl/codegen/rpc_method.h>
|
||||||
#include <grpcpp/impl/codegen/rpc_method.h>
|
#include <grpc++/impl/codegen/service_type.h>
|
||||||
#include <grpcpp/impl/codegen/service_type.h>
|
#include <grpc++/impl/codegen/status.h>
|
||||||
#include <grpcpp/impl/codegen/status.h>
|
#include <grpc++/impl/codegen/stub_options.h>
|
||||||
#include <grpcpp/impl/codegen/stub_options.h>
|
#include <grpc++/impl/codegen/sync_stream.h>
|
||||||
#include <grpcpp/impl/codegen/sync_stream.h>
|
|
||||||
|
|
||||||
namespace grpc {
|
namespace grpc {
|
||||||
class CompletionQueue;
|
class CompletionQueue;
|
||||||
class Channel;
|
class Channel;
|
||||||
|
class RpcService;
|
||||||
class ServerCompletionQueue;
|
class ServerCompletionQueue;
|
||||||
class ServerContext;
|
class ServerContext;
|
||||||
} // namespace grpc
|
} // namespace grpc
|
||||||
@@ -28,9 +28,6 @@ namespace pybullet_grpc {
|
|||||||
|
|
||||||
class PyBulletAPI final {
|
class PyBulletAPI final {
|
||||||
public:
|
public:
|
||||||
static constexpr char const* service_full_name() {
|
|
||||||
return "pybullet_grpc.PyBulletAPI";
|
|
||||||
}
|
|
||||||
class StubInterface {
|
class StubInterface {
|
||||||
public:
|
public:
|
||||||
virtual ~StubInterface() {}
|
virtual ~StubInterface() {}
|
||||||
@@ -39,12 +36,8 @@ class PyBulletAPI final {
|
|||||||
std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::pybullet_grpc::PyBulletStatus>> AsyncSubmitCommand(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) {
|
std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::pybullet_grpc::PyBulletStatus>> AsyncSubmitCommand(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) {
|
||||||
return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::pybullet_grpc::PyBulletStatus>>(AsyncSubmitCommandRaw(context, request, cq));
|
return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::pybullet_grpc::PyBulletStatus>>(AsyncSubmitCommandRaw(context, request, cq));
|
||||||
}
|
}
|
||||||
std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::pybullet_grpc::PyBulletStatus>> PrepareAsyncSubmitCommand(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) {
|
|
||||||
return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::pybullet_grpc::PyBulletStatus>>(PrepareAsyncSubmitCommandRaw(context, request, cq));
|
|
||||||
}
|
|
||||||
private:
|
private:
|
||||||
virtual ::grpc::ClientAsyncResponseReaderInterface< ::pybullet_grpc::PyBulletStatus>* AsyncSubmitCommandRaw(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) = 0;
|
virtual ::grpc::ClientAsyncResponseReaderInterface< ::pybullet_grpc::PyBulletStatus>* AsyncSubmitCommandRaw(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) = 0;
|
||||||
virtual ::grpc::ClientAsyncResponseReaderInterface< ::pybullet_grpc::PyBulletStatus>* PrepareAsyncSubmitCommandRaw(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) = 0;
|
|
||||||
};
|
};
|
||||||
class Stub final : public StubInterface {
|
class Stub final : public StubInterface {
|
||||||
public:
|
public:
|
||||||
@@ -53,15 +46,11 @@ class PyBulletAPI final {
|
|||||||
std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>> AsyncSubmitCommand(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) {
|
std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>> AsyncSubmitCommand(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) {
|
||||||
return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>>(AsyncSubmitCommandRaw(context, request, cq));
|
return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>>(AsyncSubmitCommandRaw(context, request, cq));
|
||||||
}
|
}
|
||||||
std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>> PrepareAsyncSubmitCommand(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) {
|
|
||||||
return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>>(PrepareAsyncSubmitCommandRaw(context, request, cq));
|
|
||||||
}
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
std::shared_ptr< ::grpc::ChannelInterface> channel_;
|
std::shared_ptr< ::grpc::ChannelInterface> channel_;
|
||||||
::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>* AsyncSubmitCommandRaw(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) override;
|
::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>* AsyncSubmitCommandRaw(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) override;
|
||||||
::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>* PrepareAsyncSubmitCommandRaw(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) override;
|
const ::grpc::RpcMethod rpcmethod_SubmitCommand_;
|
||||||
const ::grpc::internal::RpcMethod rpcmethod_SubmitCommand_;
|
|
||||||
};
|
};
|
||||||
static std::unique_ptr<Stub> NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions());
|
static std::unique_ptr<Stub> NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions());
|
||||||
|
|
||||||
@@ -84,7 +73,7 @@ class PyBulletAPI final {
|
|||||||
BaseClassMustBeDerivedFromService(this);
|
BaseClassMustBeDerivedFromService(this);
|
||||||
}
|
}
|
||||||
// disable synchronous version of this method
|
// disable synchronous version of this method
|
||||||
::grpc::Status SubmitCommand(::grpc::ServerContext* context, const ::pybullet_grpc::PyBulletCommand* request, ::pybullet_grpc::PyBulletStatus* response) override {
|
::grpc::Status SubmitCommand(::grpc::ServerContext* context, const ::pybullet_grpc::PyBulletCommand* request, ::pybullet_grpc::PyBulletStatus* response) final override {
|
||||||
abort();
|
abort();
|
||||||
return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, "");
|
return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, "");
|
||||||
}
|
}
|
||||||
@@ -105,45 +94,25 @@ class PyBulletAPI final {
|
|||||||
BaseClassMustBeDerivedFromService(this);
|
BaseClassMustBeDerivedFromService(this);
|
||||||
}
|
}
|
||||||
// disable synchronous version of this method
|
// disable synchronous version of this method
|
||||||
::grpc::Status SubmitCommand(::grpc::ServerContext* context, const ::pybullet_grpc::PyBulletCommand* request, ::pybullet_grpc::PyBulletStatus* response) override {
|
::grpc::Status SubmitCommand(::grpc::ServerContext* context, const ::pybullet_grpc::PyBulletCommand* request, ::pybullet_grpc::PyBulletStatus* response) final override {
|
||||||
abort();
|
abort();
|
||||||
return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, "");
|
return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, "");
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
template <class BaseClass>
|
template <class BaseClass>
|
||||||
class WithRawMethod_SubmitCommand : public BaseClass {
|
|
||||||
private:
|
|
||||||
void BaseClassMustBeDerivedFromService(const Service *service) {}
|
|
||||||
public:
|
|
||||||
WithRawMethod_SubmitCommand() {
|
|
||||||
::grpc::Service::MarkMethodRaw(0);
|
|
||||||
}
|
|
||||||
~WithRawMethod_SubmitCommand() override {
|
|
||||||
BaseClassMustBeDerivedFromService(this);
|
|
||||||
}
|
|
||||||
// disable synchronous version of this method
|
|
||||||
::grpc::Status SubmitCommand(::grpc::ServerContext* context, const ::pybullet_grpc::PyBulletCommand* request, ::pybullet_grpc::PyBulletStatus* response) override {
|
|
||||||
abort();
|
|
||||||
return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, "");
|
|
||||||
}
|
|
||||||
void RequestSubmitCommand(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) {
|
|
||||||
::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag);
|
|
||||||
}
|
|
||||||
};
|
|
||||||
template <class BaseClass>
|
|
||||||
class WithStreamedUnaryMethod_SubmitCommand : public BaseClass {
|
class WithStreamedUnaryMethod_SubmitCommand : public BaseClass {
|
||||||
private:
|
private:
|
||||||
void BaseClassMustBeDerivedFromService(const Service *service) {}
|
void BaseClassMustBeDerivedFromService(const Service *service) {}
|
||||||
public:
|
public:
|
||||||
WithStreamedUnaryMethod_SubmitCommand() {
|
WithStreamedUnaryMethod_SubmitCommand() {
|
||||||
::grpc::Service::MarkMethodStreamed(0,
|
::grpc::Service::MarkMethodStreamed(0,
|
||||||
new ::grpc::internal::StreamedUnaryHandler< ::pybullet_grpc::PyBulletCommand, ::pybullet_grpc::PyBulletStatus>(std::bind(&WithStreamedUnaryMethod_SubmitCommand<BaseClass>::StreamedSubmitCommand, this, std::placeholders::_1, std::placeholders::_2)));
|
new ::grpc::StreamedUnaryHandler< ::pybullet_grpc::PyBulletCommand, ::pybullet_grpc::PyBulletStatus>(std::bind(&WithStreamedUnaryMethod_SubmitCommand<BaseClass>::StreamedSubmitCommand, this, std::placeholders::_1, std::placeholders::_2)));
|
||||||
}
|
}
|
||||||
~WithStreamedUnaryMethod_SubmitCommand() override {
|
~WithStreamedUnaryMethod_SubmitCommand() override {
|
||||||
BaseClassMustBeDerivedFromService(this);
|
BaseClassMustBeDerivedFromService(this);
|
||||||
}
|
}
|
||||||
// disable regular version of this method
|
// disable regular version of this method
|
||||||
::grpc::Status SubmitCommand(::grpc::ServerContext* context, const ::pybullet_grpc::PyBulletCommand* request, ::pybullet_grpc::PyBulletStatus* response) override {
|
::grpc::Status SubmitCommand(::grpc::ServerContext* context, const ::pybullet_grpc::PyBulletCommand* request, ::pybullet_grpc::PyBulletStatus* response) final override {
|
||||||
abort();
|
abort();
|
||||||
return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, "");
|
return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, "");
|
||||||
}
|
}
|
||||||
|
|||||||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@@ -18,6 +18,9 @@ struct b3PluginContext
|
|||||||
int m_numMouseEvents;
|
int m_numMouseEvents;
|
||||||
const struct b3Notification* m_notifications;
|
const struct b3Notification* m_notifications;
|
||||||
int m_numNotifications;
|
int m_numNotifications;
|
||||||
|
|
||||||
|
//only used for grpc/processClientCommands
|
||||||
|
class PhysicsCommandProcessorInterface* m_rpcCommandProcessorInterface;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
354
examples/SharedMemory/plugins/grpcPlugin/grpcPlugin.cpp
Normal file
354
examples/SharedMemory/plugins/grpcPlugin/grpcPlugin.cpp
Normal file
@@ -0,0 +1,354 @@
|
|||||||
|
|
||||||
|
//tinyRendererPlugin implements the TinyRenderer as a plugin
|
||||||
|
//it is statically linked when using preprocessor #define STATIC_LINK_VR_PLUGIN
|
||||||
|
//otherwise you can dynamically load it using pybullet.loadPlugin
|
||||||
|
|
||||||
|
#include "grpcPlugin.h"
|
||||||
|
#include "../../SharedMemoryPublic.h"
|
||||||
|
#include "../b3PluginContext.h"
|
||||||
|
#include "Bullet3Common/b3AlignedObjectArray.h"
|
||||||
|
#include "SharedMemoryCommands.h"
|
||||||
|
#include "PhysicsCommandProcessorInterface.h"
|
||||||
|
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
|
#include <grpc++/grpc++.h>
|
||||||
|
#include <grpc/support/log.h>
|
||||||
|
#include "../../../Utils/b3Clock.h"
|
||||||
|
#include "../../grpc/pybullet.grpc.pb.h"
|
||||||
|
#include "../../grpc/ConvertGRPCBullet.h"
|
||||||
|
using grpc::Server;
|
||||||
|
using grpc::ServerAsyncResponseWriter;
|
||||||
|
using grpc::ServerBuilder;
|
||||||
|
using grpc::ServerContext;
|
||||||
|
using grpc::ServerCompletionQueue;
|
||||||
|
using grpc::Status;
|
||||||
|
using pybullet_grpc::PyBulletCommand;
|
||||||
|
using pybullet_grpc::PyBulletStatus;
|
||||||
|
using pybullet_grpc::PyBulletAPI;
|
||||||
|
|
||||||
|
|
||||||
|
bool gVerboseNetworkMessagesServer4 = true;
|
||||||
|
|
||||||
|
|
||||||
|
class ServerImpl final {
|
||||||
|
public:
|
||||||
|
|
||||||
|
ServerImpl()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
~ServerImpl() {
|
||||||
|
Exit();
|
||||||
|
}
|
||||||
|
|
||||||
|
void Exit()
|
||||||
|
{
|
||||||
|
if (server_)
|
||||||
|
{
|
||||||
|
server_->Shutdown();
|
||||||
|
// Always shutdown the completion queue after the server.
|
||||||
|
cq_->Shutdown();
|
||||||
|
server_ = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Init(PhysicsCommandProcessorInterface* comProc, const std::string& hostNamePort) {
|
||||||
|
|
||||||
|
// Listen on the given address without any authentication mechanism.
|
||||||
|
m_builder.AddListeningPort(hostNamePort, grpc::InsecureServerCredentials());
|
||||||
|
// Register "service_" as the instance through which we'll communicate with
|
||||||
|
// clients. In this case it corresponds to an *asynchronous* service.
|
||||||
|
m_builder.RegisterService(&service_);
|
||||||
|
// Get hold of the completion queue used for the asynchronous communication
|
||||||
|
// with the gRPC runtime.
|
||||||
|
cq_ = m_builder.AddCompletionQueue();
|
||||||
|
// Finally assemble the server.
|
||||||
|
server_ = m_builder.BuildAndStart();
|
||||||
|
std::cout << "Server listening on " << hostNamePort << std::endl;
|
||||||
|
|
||||||
|
// Proceed to the server's main loop.
|
||||||
|
InitRpcs(comProc);
|
||||||
|
}
|
||||||
|
|
||||||
|
// This can be run in multiple threads if needed.
|
||||||
|
bool HandleSingleRpc()
|
||||||
|
{
|
||||||
|
|
||||||
|
CallData::CallStatus status = CallData::CallStatus::CREATE;
|
||||||
|
|
||||||
|
{
|
||||||
|
void* tag; // uniquely identifies a request.
|
||||||
|
bool ok;
|
||||||
|
|
||||||
|
// Block waiting to read the next event from the completion queue. The
|
||||||
|
// event is uniquely identified by its tag, which in this case is the
|
||||||
|
// memory address of a CallData instance.
|
||||||
|
// The return value of Next should always be checked. This return value
|
||||||
|
// tells us whether there is any kind of event or cq_ is shutting down.
|
||||||
|
|
||||||
|
grpc::CompletionQueue::NextStatus nextStatus = cq_->AsyncNext(&tag, &ok, gpr_now(GPR_CLOCK_MONOTONIC));
|
||||||
|
if (nextStatus == grpc::CompletionQueue::NextStatus::GOT_EVENT)
|
||||||
|
{
|
||||||
|
//GPR_ASSERT(cq_->Next(&tag, &ok));
|
||||||
|
GPR_ASSERT(ok);
|
||||||
|
status = static_cast<CallData*>(tag)->Proceed();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return status == CallData::CallStatus::TERMINATE;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
// Class encompasing the state and logic needed to serve a request.
|
||||||
|
class CallData {
|
||||||
|
public:
|
||||||
|
// Take in the "service" instance (in this case representing an asynchronous
|
||||||
|
// server) and the completion queue "cq" used for asynchronous communication
|
||||||
|
// with the gRPC runtime.
|
||||||
|
CallData(PyBulletAPI::AsyncService* service, ServerCompletionQueue* cq, PhysicsCommandProcessorInterface* comProc)
|
||||||
|
: service_(service), cq_(cq), responder_(&ctx_), status_(CREATE), m_finished(false), m_comProc(comProc) {
|
||||||
|
// Invoke the serving logic right away.
|
||||||
|
Proceed();
|
||||||
|
}
|
||||||
|
|
||||||
|
enum CallStatus { CREATE, PROCESS, FINISH, TERMINATE };
|
||||||
|
|
||||||
|
CallStatus Proceed() {
|
||||||
|
if (status_ == CREATE) {
|
||||||
|
// Make this instance progress to the PROCESS state.
|
||||||
|
status_ = PROCESS;
|
||||||
|
|
||||||
|
// As part of the initial CREATE state, we *request* that the system
|
||||||
|
// start processing SayHello requests. In this request, "this" acts are
|
||||||
|
// the tag uniquely identifying the request (so that different CallData
|
||||||
|
// instances can serve different requests concurrently), in this case
|
||||||
|
// the memory address of this CallData instance.
|
||||||
|
|
||||||
|
|
||||||
|
service_->RequestSubmitCommand(&ctx_, &m_command, &responder_, cq_, cq_,
|
||||||
|
this);
|
||||||
|
}
|
||||||
|
else if (status_ == PROCESS) {
|
||||||
|
// Spawn a new CallData instance to serve new clients while we process
|
||||||
|
// the one for this CallData. The instance will deallocate itself as
|
||||||
|
// part of its FINISH state.
|
||||||
|
new CallData(service_, cq_, m_comProc);
|
||||||
|
status_ = FINISH;
|
||||||
|
|
||||||
|
std::string replyString;
|
||||||
|
// The actual processing.
|
||||||
|
|
||||||
|
SharedMemoryStatus serverStatus;
|
||||||
|
b3AlignedObjectArray<char> buffer;
|
||||||
|
buffer.resize(SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
|
||||||
|
SharedMemoryCommand cmd;
|
||||||
|
SharedMemoryCommand* cmdPtr = 0;
|
||||||
|
|
||||||
|
m_status.set_statustype(CMD_UNKNOWN_COMMAND_FLUSHED);
|
||||||
|
|
||||||
|
|
||||||
|
if (m_command.has_checkversioncommand())
|
||||||
|
{
|
||||||
|
m_status.set_statustype(CMD_CLIENT_COMMAND_COMPLETED);
|
||||||
|
m_status.mutable_checkversionstatus()->set_serverversion(SHARED_MEMORY_MAGIC_NUMBER);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
cmdPtr = convertGRPCToBulletCommand(m_command, cmd);
|
||||||
|
|
||||||
|
|
||||||
|
if (cmdPtr)
|
||||||
|
{
|
||||||
|
bool hasStatus = m_comProc->processCommand(*cmdPtr, serverStatus, &buffer[0], buffer.size());
|
||||||
|
|
||||||
|
double timeOutInSeconds = 10;
|
||||||
|
b3Clock clock;
|
||||||
|
double startTimeSeconds = clock.getTimeInSeconds();
|
||||||
|
double curTimeSeconds = clock.getTimeInSeconds();
|
||||||
|
|
||||||
|
while ((!hasStatus) && ((curTimeSeconds - startTimeSeconds) < timeOutInSeconds))
|
||||||
|
{
|
||||||
|
hasStatus = m_comProc->receiveStatus(serverStatus, &buffer[0], buffer.size());
|
||||||
|
curTimeSeconds = clock.getTimeInSeconds();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gVerboseNetworkMessagesServer4)
|
||||||
|
{
|
||||||
|
//printf("buffer.size = %d\n", buffer.size());
|
||||||
|
printf("serverStatus.m_numDataStreamBytes = %d\n", serverStatus.m_numDataStreamBytes);
|
||||||
|
}
|
||||||
|
if (hasStatus)
|
||||||
|
{
|
||||||
|
b3AlignedObjectArray<unsigned char> packetData;
|
||||||
|
unsigned char* statBytes = (unsigned char*)&serverStatus;
|
||||||
|
|
||||||
|
convertStatusToGRPC(serverStatus, &buffer[0], buffer.size(), m_status);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (m_command.has_terminateservercommand())
|
||||||
|
{
|
||||||
|
status_ = TERMINATE;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// And we are done! Let the gRPC runtime know we've finished, using the
|
||||||
|
// memory address of this instance as the uniquely identifying tag for
|
||||||
|
// the event.
|
||||||
|
|
||||||
|
responder_.Finish(m_status, Status::OK, this);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
GPR_ASSERT(status_ == FINISH);
|
||||||
|
// Once in the FINISH state, deallocate ourselves (CallData).
|
||||||
|
delete this;
|
||||||
|
}
|
||||||
|
return status_;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
// The means of communication with the gRPC runtime for an asynchronous
|
||||||
|
// server.
|
||||||
|
PyBulletAPI::AsyncService* service_;
|
||||||
|
// The producer-consumer queue where for asynchronous server notifications.
|
||||||
|
ServerCompletionQueue* cq_;
|
||||||
|
// Context for the rpc, allowing to tweak aspects of it such as the use
|
||||||
|
// of compression, authentication, as well as to send metadata back to the
|
||||||
|
// client.
|
||||||
|
ServerContext ctx_;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
// What we get from the client.
|
||||||
|
PyBulletCommand m_command;
|
||||||
|
// What we send back to the client.
|
||||||
|
PyBulletStatus m_status;
|
||||||
|
|
||||||
|
// The means to get back to the client.
|
||||||
|
ServerAsyncResponseWriter<PyBulletStatus> responder_;
|
||||||
|
|
||||||
|
// Let's implement a tiny state machine with the following states.
|
||||||
|
|
||||||
|
CallStatus status_; // The current serving state.
|
||||||
|
|
||||||
|
bool m_finished;
|
||||||
|
|
||||||
|
PhysicsCommandProcessorInterface* m_comProc; //physics server command processor
|
||||||
|
};
|
||||||
|
|
||||||
|
// This can be run in multiple threads if needed.
|
||||||
|
void InitRpcs(PhysicsCommandProcessorInterface* comProc)
|
||||||
|
{
|
||||||
|
// Spawn a new CallData instance to serve new clients.
|
||||||
|
new CallData(&service_, cq_.get(), comProc);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
ServerBuilder m_builder;
|
||||||
|
std::unique_ptr<ServerCompletionQueue> cq_;
|
||||||
|
PyBulletAPI::AsyncService service_;
|
||||||
|
std::unique_ptr<Server> server_;
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
struct grpcMyClass
|
||||||
|
{
|
||||||
|
int m_testData;
|
||||||
|
|
||||||
|
ServerImpl m_grpcServer;
|
||||||
|
bool m_grpcInitialized;
|
||||||
|
bool m_grpcTerminated;
|
||||||
|
|
||||||
|
grpcMyClass()
|
||||||
|
:m_testData(42),
|
||||||
|
m_grpcInitialized(false),
|
||||||
|
m_grpcTerminated(false)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
virtual ~grpcMyClass()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
B3_SHARED_API int initPlugin_grpcPlugin(struct b3PluginContext* context)
|
||||||
|
{
|
||||||
|
grpcMyClass* obj = new grpcMyClass();
|
||||||
|
context->m_userPointer = obj;
|
||||||
|
|
||||||
|
|
||||||
|
return SHARED_MEMORY_MAGIC_NUMBER;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
B3_SHARED_API int preTickPluginCallback_grpcPlugin(struct b3PluginContext* context)
|
||||||
|
{
|
||||||
|
//process grpc server messages
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API int processClientCommands_grpcPlugin(struct b3PluginContext* context)
|
||||||
|
{
|
||||||
|
grpcMyClass* obj = (grpcMyClass*)context->m_userPointer;
|
||||||
|
|
||||||
|
if (obj->m_grpcInitialized && !obj->m_grpcTerminated)
|
||||||
|
{
|
||||||
|
obj->m_grpcTerminated = obj->m_grpcServer.HandleSingleRpc();
|
||||||
|
}
|
||||||
|
|
||||||
|
obj->m_testData++;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API int postTickPluginCallback_grpcPlugin(struct b3PluginContext* context)
|
||||||
|
{
|
||||||
|
grpcMyClass* obj = (grpcMyClass* )context->m_userPointer;
|
||||||
|
obj->m_testData++;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API int executePluginCommand_grpcPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments)
|
||||||
|
{
|
||||||
|
///3 cases:
|
||||||
|
/// 1: send a non-empty string to start the GRPC server
|
||||||
|
/// 2: send some integer n, to call n times to HandleSingleRpc
|
||||||
|
/// 3: send nothing to terminate the GRPC server
|
||||||
|
|
||||||
|
grpcMyClass* obj = (grpcMyClass*)context->m_userPointer;
|
||||||
|
|
||||||
|
if (arguments->m_text && strlen(arguments->m_text))
|
||||||
|
{
|
||||||
|
if (!obj->m_grpcInitialized && context->m_rpcCommandProcessorInterface)
|
||||||
|
{
|
||||||
|
obj->m_grpcServer.Init(context->m_rpcCommandProcessorInterface, arguments->m_text);
|
||||||
|
}
|
||||||
|
obj->m_grpcInitialized = true;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
if (arguments->m_numInts > 0)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < arguments->m_ints[0]; i++)
|
||||||
|
{
|
||||||
|
if (obj->m_grpcInitialized && !obj->m_grpcTerminated)
|
||||||
|
{
|
||||||
|
obj->m_grpcTerminated = obj->m_grpcServer.HandleSingleRpc();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
obj->m_grpcServer.Exit();
|
||||||
|
obj->m_grpcInitialized = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
B3_SHARED_API void exitPlugin_grpcPlugin(struct b3PluginContext* context)
|
||||||
|
{
|
||||||
|
grpcMyClass* obj = (grpcMyClass*) context->m_userPointer;
|
||||||
|
obj->m_grpcServer.Exit();
|
||||||
|
delete obj;
|
||||||
|
context->m_userPointer = 0;
|
||||||
|
}
|
||||||
29
examples/SharedMemory/plugins/grpcPlugin/grpcPlugin.h
Normal file
29
examples/SharedMemory/plugins/grpcPlugin/grpcPlugin.h
Normal file
@@ -0,0 +1,29 @@
|
|||||||
|
#ifndef GRPC_PLUGIN_H
|
||||||
|
#define GRPC_PLUGIN_H
|
||||||
|
|
||||||
|
#include "../b3PluginAPI.h"
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//the following 3 APIs are required
|
||||||
|
B3_SHARED_API int initPlugin_grpcPlugin(struct b3PluginContext* context);
|
||||||
|
B3_SHARED_API void exitPlugin_grpcPlugin(struct b3PluginContext* context);
|
||||||
|
B3_SHARED_API int executePluginCommand_grpcPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
|
||||||
|
|
||||||
|
//all the APIs below are optional
|
||||||
|
B3_SHARED_API int preTickPluginCallback_grpcPlugin(struct b3PluginContext* context);
|
||||||
|
B3_SHARED_API int postTickPluginCallback_grpcPlugin(struct b3PluginContext* context);
|
||||||
|
|
||||||
|
B3_SHARED_API int processClientCommands_grpcPlugin(struct b3PluginContext* context);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif//#define GRPC_PLUGIN_H
|
||||||
43
examples/SharedMemory/plugins/grpcPlugin/premake4.lua
Normal file
43
examples/SharedMemory/plugins/grpcPlugin/premake4.lua
Normal file
@@ -0,0 +1,43 @@
|
|||||||
|
|
||||||
|
|
||||||
|
project ("pybullet_grpcPlugin")
|
||||||
|
language "C++"
|
||||||
|
kind "SharedLib"
|
||||||
|
|
||||||
|
includedirs {".","../../../../src", "../../../../examples",
|
||||||
|
"../../../ThirdPartyLibs"}
|
||||||
|
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
|
||||||
|
|
||||||
|
initGRPC()
|
||||||
|
|
||||||
|
links{"BulletFileLoader", "Bullet3Common", "LinearMath"}
|
||||||
|
|
||||||
|
|
||||||
|
if os.is("MacOSX") then
|
||||||
|
-- targetextension {"so"}
|
||||||
|
links{"Cocoa.framework"}
|
||||||
|
end
|
||||||
|
|
||||||
|
|
||||||
|
files {
|
||||||
|
"grpcPlugin.cpp",
|
||||||
|
"../../PhysicsClient.cpp",
|
||||||
|
"../../PhysicsClient.h",
|
||||||
|
"../../PhysicsClientSharedMemory.cpp",
|
||||||
|
"../../PhysicsClientSharedMemory.h",
|
||||||
|
"../../PhysicsClientSharedMemory_C_API.cpp",
|
||||||
|
"../../PhysicsClientSharedMemory_C_API.h",
|
||||||
|
"../../PhysicsClientC_API.cpp",
|
||||||
|
"../../PhysicsClientC_API.h",
|
||||||
|
"../../Win32SharedMemory.cpp",
|
||||||
|
"../../Win32SharedMemory.h",
|
||||||
|
"../../PosixSharedMemory.cpp",
|
||||||
|
"../../PosixSharedMemory.h",
|
||||||
|
"../../../Utils/b3Clock.cpp",
|
||||||
|
"../../../Utils/b3Clock.h",
|
||||||
|
"../../../Utils/b3ResourcePath.cpp",
|
||||||
|
"../../../Utils/b3ResourcePath.h",
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
@@ -476,4 +476,5 @@ include "plugins/collisionFilterPlugin"
|
|||||||
|
|
||||||
if _OPTIONS["enable_grpc"] then
|
if _OPTIONS["enable_grpc"] then
|
||||||
include "grpc"
|
include "grpc"
|
||||||
|
include "plugins/grpcPlugin"
|
||||||
end
|
end
|
||||||
|
|||||||
@@ -4,6 +4,17 @@ project ("pybullet")
|
|||||||
language "C++"
|
language "C++"
|
||||||
kind "SharedLib"
|
kind "SharedLib"
|
||||||
|
|
||||||
|
if _OPTIONS["enable_grpc"] then
|
||||||
|
initGRPC()
|
||||||
|
|
||||||
|
files {
|
||||||
|
"../../examples/SharedMemory/PhysicsClientGRPC.cpp",
|
||||||
|
"../../examples/SharedMemory/PhysicsClientGRPC.h",
|
||||||
|
"../../examples/SharedMemory/PhysicsClientGRPC_C_API.cpp",
|
||||||
|
"../../examples/SharedMemory/PhysicsClientGRPC_C_API.h",
|
||||||
|
}
|
||||||
|
end
|
||||||
|
|
||||||
includedirs {"../../src", "../../examples",
|
includedirs {"../../src", "../../examples",
|
||||||
"../../examples/ThirdPartyLibs"}
|
"../../examples/ThirdPartyLibs"}
|
||||||
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
|
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
|
||||||
|
|||||||
@@ -437,7 +437,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
|||||||
case eCONNECT_GRPC:
|
case eCONNECT_GRPC:
|
||||||
{
|
{
|
||||||
#ifdef BT_ENABLE_GRPC
|
#ifdef BT_ENABLE_GRPC
|
||||||
sm = b3ConnectPhysicsGRPC(hostName.c_str(), tcpPort);
|
sm = b3ConnectPhysicsGRPC(hostName, tcpPort);
|
||||||
#else
|
#else
|
||||||
PyErr_SetString(SpamError, "GRPC is not enabled in this pybullet build");
|
PyErr_SetString(SpamError, "GRPC is not enabled in this pybullet build");
|
||||||
#endif
|
#endif
|
||||||
|
|||||||
Reference in New Issue
Block a user