bullet3/examples/pybullet/quadruped.py
erwin coumans c0fb98861d add quadruped.py script to load and initialize the a Minitaur-like quadruped
pybullet removeConstraint, createConstraint
rename b3CreateJoint to b3InitCreateUserConstraintCommand
add int b3GetStatusUserConstraintUniqueId(b3SharedMemoryStatusHandle statusHandle);
b3SharedMemoryCommandHandle  b3InitRemoveUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId);
2016-11-14 14:08:05 -08:00

35 lines
925 B
Python

import pybullet as p
p.connect(p.GUI)
p.loadURDF("plane.urdf")
p.loadURDF("quadruped/quadruped.urdf",0,0,0.2)
#p.getNumJoints(1)
#right front leg
p.resetJointState(1,0,1.57)
p.resetJointState(1,2,-2.2)
p.resetJointState(1,3,-1.57)
p.resetJointState(1,5,2.2)
p.createConstraint(1,2,1,5,3,[0,0,0],[0,0.01,0.2],[0,-0.015,0.2])
#left front leg
p.resetJointState(1,6,1.57)
p.resetJointState(1,8,-2.2)
p.resetJointState(1,9,-1.57)
p.resetJointState(1,11,2.2)
p.createConstraint(1,8,1,11,3,[0,0,0],[0,-0.01,0.2],[0,0.015,0.2])
#right back leg
p.resetJointState(1,12,1.57)
p.resetJointState(1,14,-2.2)
p.resetJointState(1,15,-1.57)
p.resetJointState(1,17,2.2)
p.createConstraint(1,14,1,17,3,[0,0,0],[0,0.01,0.2],[0,-0.015,0.2])
#left back leg
p.resetJointState(1,18,1.57)
p.resetJointState(1,20,-2.2)
p.resetJointState(1,21,-1.57)
p.resetJointState(1,23,2.2)
p.createConstraint(1,20,1,23,3,[0,0,0],[0,-0.01,0.2],[0,0.015,0.2])