bullet3/examples/SharedMemory/PhysicsCommandProcessorInterface.h
erwincoumans 0efc67841d 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])
2018-09-05 17:58:14 -07:00

69 lines
2.3 KiB
C++

#ifndef PHYSICS_COMMAND_PROCESSOR_INTERFACE_H
#define PHYSICS_COMMAND_PROCESSOR_INTERFACE_H
enum PhysicsCommandRenderFlags
{
COV_DISABLE_SYNC_RENDERING=1
};
class PhysicsCommandProcessorInterface
{
public:
virtual ~PhysicsCommandProcessorInterface() {}
virtual bool connect()=0;
virtual void disconnect() = 0;
virtual bool isConnected() const = 0;
virtual bool processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) = 0;
virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) = 0;
virtual void renderScene(int renderFlags) = 0;
virtual void physicsDebugDraw(int debugDrawFlags) = 0;
virtual void setGuiHelper(struct GUIHelperInterface* guiHelper) = 0;
virtual void setTimeOut(double timeOutInSeconds) = 0;
virtual void reportNotifications() = 0;
};
class btVector3;
class btQuaternion;
class CommandProcessorInterface : public PhysicsCommandProcessorInterface
{
public:
virtual ~CommandProcessorInterface(){}
virtual void syncPhysicsToGraphics()=0;
virtual void stepSimulationRealTime(double dtInSec,const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents)=0;
virtual void enableRealTimeSimulation(bool enableRealTimeSim)=0;
virtual bool isRealTimeSimulationEnabled() const=0;
virtual void enableCommandLogging(bool enable, const char* fileName)=0;
virtual void replayFromLogFile(const char* fileName)=0;
virtual void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes )=0;
virtual bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)=0;
virtual bool movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)=0;
virtual void removePickingConstraint()=0;
virtual const btVector3& getVRTeleportPosition() const=0;
virtual void setVRTeleportPosition(const btVector3& vrReleportPos)=0;
virtual const btQuaternion& getVRTeleportOrientation() const=0;
virtual void setVRTeleportOrientation(const btQuaternion& vrReleportOrn)=0;
virtual void processClientCommands() = 0;
};
#endif //PHYSICS_COMMAND_PROCESSOR_INTERFACE_H