examples\pybullet\examples\humanoid_knee_position_control.py : allow both knees to be actuated against limit
This commit is contained in:
@@ -11,7 +11,7 @@ useRealTime = 0
|
||||
|
||||
p.setRealTimeSimulation(useRealTime)
|
||||
|
||||
p.setGravity(0,0,0)
|
||||
p.setGravity(0,0,-10)
|
||||
|
||||
p.loadURDF("plane.urdf")
|
||||
|
||||
@@ -21,17 +21,26 @@ human = obUids[0]
|
||||
|
||||
|
||||
for i in range (p.getNumJoints(human)):
|
||||
p.setJointMotorControl2(human,i,p.POSITION_CONTROL,targetPosition=0,force=50)
|
||||
p.setJointMotorControl2(human,i,p.POSITION_CONTROL,targetPosition=0,force=500)
|
||||
|
||||
kneeAngleTargetId = p.addUserDebugParameter("kneeAngle",-4,4,-1)
|
||||
maxForceId = p.addUserDebugParameter("maxForce",0,100,10)
|
||||
maxForceId = p.addUserDebugParameter("maxForce",0,500,10)
|
||||
|
||||
kneeAngleTargetLeftId = p.addUserDebugParameter("kneeAngleL",-4,4,-1)
|
||||
maxForceLeftId = p.addUserDebugParameter("maxForceL",0,500,10)
|
||||
|
||||
|
||||
kneeJointIndex=11
|
||||
kneeJointIndexLeft=18
|
||||
|
||||
while (1):
|
||||
time.sleep(0.01)
|
||||
kneeAngleTarget = p.readUserDebugParameter(kneeAngleTargetId)
|
||||
maxForce = p.readUserDebugParameter(maxForceId)
|
||||
p.setJointMotorControl2(human,kneeJointIndex,p.POSITION_CONTROL,targetPosition=kneeAngleTarget,force=maxForce)
|
||||
kneeAngleTargetLeft = p.readUserDebugParameter(kneeAngleTargetLeftId)
|
||||
maxForceLeft = p.readUserDebugParameter(maxForceLeftId)
|
||||
p.setJointMotorControl2(human,kneeJointIndexLeft,p.POSITION_CONTROL,targetPosition=kneeAngleTargetLeft,force=maxForceLeft)
|
||||
|
||||
if (useRealTime==0):
|
||||
p.stepSimulation()
|
||||
Reference in New Issue
Block a user