use grpc port -1 by default in PyBullet. add grpcClient.py and grpcServer.py
This commit is contained in:
19
examples/pybullet/examples/grpcClient.py
Normal file
19
examples/pybullet/examples/grpcClient.py
Normal file
@@ -0,0 +1,19 @@
|
||||
|
||||
import pybullet as p
|
||||
|
||||
usePort = True
|
||||
|
||||
if (usePort):
|
||||
id = p.connect(p.GRPC,"localhost:12345")
|
||||
else:
|
||||
id = p.connect(p.GRPC,"localhost")
|
||||
print("id=",id)
|
||||
|
||||
if (id<0):
|
||||
print("Cannot connect to GRPC server")
|
||||
exit(0)
|
||||
|
||||
print ("Connected to GRPC")
|
||||
r2d2 = p.loadURDF("r2d2.urdf")
|
||||
print("numJoints = ", p.getNumJoints(r2d2))
|
||||
|
||||
29
examples/pybullet/examples/grpcServer.py
Normal file
29
examples/pybullet/examples/grpcServer.py
Normal file
@@ -0,0 +1,29 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
useDirect = False
|
||||
usePort = True
|
||||
|
||||
p.connect(p.GUI)
|
||||
id = p.loadPlugin("grpcPlugin")
|
||||
#dynamically 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):
|
||||
print("Cannot load grpcPlugin")
|
||||
exit(0)
|
||||
|
||||
if usePort:
|
||||
p.executePluginCommand(id, "localhost:12345")
|
||||
else:
|
||||
p.executePluginCommand(id, "localhost")
|
||||
|
||||
while p.isConnected():
|
||||
if (useDirect):
|
||||
#Only in DIRECT mode, since there is no 'ping' you need to manually call to handle RCPs:
|
||||
numRPC = 10
|
||||
p.executePluginCommand(id, intArgs=[numRPC])
|
||||
else:
|
||||
dt = 1./240.
|
||||
time.sleep(dt)
|
||||
Reference in New Issue
Block a user