add pybullet.changeConstraint / b3InitChangeUserConstraintCommand/ b3InitChangeUserConstraintSetPivotInB /b3InitChangeUserConstraintSetFrameInB command, to change an existing user constraint.
add constraint.py example.
allow pybullet.createConstraint to create user constraint without a child body ('fixed' to the world)
This commit is contained in:
24
examples/pybullet/constraint.py
Normal file
24
examples/pybullet/constraint.py
Normal file
@@ -0,0 +1,24 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import math
|
||||
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.loadURDF("plane.urdf")
|
||||
cubeId = p.loadURDF("cube_small.urdf",0,0,1)
|
||||
p.setGravity(0,0,-10)
|
||||
p.setRealTimeSimulation(1)
|
||||
cid = p.createConstraint(cubeId,-1,-1,-1,p.JOINT_FIXED,[0,0,0],[0,0,0],[0,0,1])
|
||||
|
||||
a=-math.pi
|
||||
while 1:
|
||||
a=a+0.01
|
||||
if (a>math.pi):
|
||||
a=-math.pi
|
||||
time.sleep(.01)
|
||||
p.setGravity(0,0,-10)
|
||||
pivot=[a,0,1]
|
||||
orn = p.getQuaternionFromEuler([a,0,0])
|
||||
p.changeConstraint(cid,pivot,jointChildFrameOrientation=orn)
|
||||
|
||||
p.removeConstraint(cid)
|
||||
Reference in New Issue
Block a user