implement 'mimic' joint constraint or 'gear' constraint for btMultiBody, add example in pybullet/examples/mimicJointConstraint.py
This commit is contained in:
@@ -1,16 +1,19 @@
|
||||
#mimic joint currently only works for 'maximal coordinate' rigid bodies
|
||||
#one way to use it would be to attach maximal coordinate rigid bodies to multibody links using
|
||||
#fixed constraints
|
||||
#a mimic joint can act as a gear between two joints
|
||||
#you can control the gear ratio in magnitude and sign (>0 reverses direction)
|
||||
|
||||
import pybullet as p
|
||||
import time
|
||||
p.connect(p.GUI)
|
||||
wheelA = p.loadURDF("wheel.urdf",[0,0,0],useMaximalCoordinates=1)
|
||||
wheelB = p.loadURDF("wheel.urdf",[0,0,1],useMaximalCoordinates=1)
|
||||
c = p.createConstraint(wheelA,-1,wheelB,-1,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-0.1)
|
||||
wheelA = p.loadURDF("wheel.urdf",[0,0,0])
|
||||
wheelB = p.loadURDF("wheel.urdf",[0,0,1])
|
||||
p.setJointMotorControl2(wheelA,0,p.VELOCITY_CONTROL,targetVelocity=0,force=0)
|
||||
p.setJointMotorControl2(wheelB,0,p.VELOCITY_CONTROL,targetVelocity=1,force=1)
|
||||
|
||||
c = p.createConstraint(wheelA,0,wheelB,0,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||
p.changeConstraint(c,gearRatio=-0.1, maxForce=10000)
|
||||
|
||||
p.setRealTimeSimulation(1)
|
||||
while(1):
|
||||
time.sleep(0.01)
|
||||
p.removeConstraint(c)
|
||||
#p.removeConstraint(c)
|
||||
|
||||
Reference in New Issue
Block a user