pybullet, more robust multi-server connections
Windows shared memory: allow to use custom key. Improve GUI performance on Windows, submit letters in text as a batch (fewer draw-calls) quadruped.py: first try to connect to SHARED_MEMORY, if it fails (<0) use GUI increase Chrome about://tracing json export capacity (press 'p' in Example Browser) UDP physics server: add --port and --sharedMemoryKey command-line arguments PhysicsServerExample: add --sharedMemoryKey command-line option (for VR example too) ExampleBrowser: sleep a few milliseconds if rendering is too fast, use --minUpdateTimeMicroSecs=0 to disable
This commit is contained in:
@@ -2,11 +2,15 @@ import pybullet as p
|
||||
import time
|
||||
import math
|
||||
|
||||
p.connect(p.SHARED_MEMORY)
|
||||
|
||||
physId = p.connect(p.SHARED_MEMORY)
|
||||
if (physId<0):
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.loadURDF("plane.urdf")
|
||||
p.setGravity(0,0,-1)
|
||||
p.setRealTimeSimulation(0)
|
||||
quadruped = p.loadURDF("quadruped/quadruped.urdf",10,-2,2)
|
||||
quadruped = p.loadURDF("quadruped/quadruped.urdf",1,-2,2)
|
||||
#p.getNumJoints(1)
|
||||
#right front leg
|
||||
p.resetJointState(quadruped,0,1.57)
|
||||
@@ -82,6 +86,7 @@ jump_amp = 0.5
|
||||
#jump
|
||||
t_end = time.time() + 10
|
||||
i=0
|
||||
t=0
|
||||
while time.time() < t_end:
|
||||
t = time.time()
|
||||
p.setJointMotorControl(quadruped,0,p.POSITION_CONTROL,math.sin(t*speed)*jump_amp+1.57,p_gain)
|
||||
|
||||
Reference in New Issue
Block a user