mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 21:30:09 +00:00
add friction_anchor to microtaur.urdf
This commit is contained in:
parent
a42acfbe31
commit
a0b7b2a47c
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
@ -0,0 +1,14 @@
|
||||
import pybullet as p
|
||||
cin = p.connect(p.SHARED_MEMORY)
|
||||
if (cin < 0):
|
||||
cin = p.connect(p.GUI)
|
||||
objects = [p.loadURDF("plane_transparent.urdf", 0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.000000)]
|
||||
objects = [p.loadURDF("microtaur.urdf", -0.505314,0.078555,0.228410,-0.013472,-0.004258,0.359966,0.932858)]
|
||||
ob = objects[0]
|
||||
jointPositions=[ 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 1.562331, 0.000000, -0.730446, -1.420420, -1.388973, 0.000000, -0.755517, -1.353138, 0.000000, 0.000000, 0.000000, 0.000000, 1.521366, 0.000000, -0.766233, -1.517965, 1.432633, 0.000000, -0.797550, -1.514139 ]
|
||||
for jointIndex in range (p.getNumJoints(ob)):
|
||||
p.resetJointState(ob,jointIndex,jointPositions[jointIndex])
|
||||
|
||||
p.setGravity(0.000000,0.000000,-10.000000)
|
||||
p.stepSimulation()
|
||||
p.disconnect()
|
@ -0,0 +1,42 @@
|
||||
import pybullet as p
|
||||
import pybullet_data as pd
|
||||
import time
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pd.getDataPath())
|
||||
|
||||
plane = p.loadURDF("plane_transparent.urdf")
|
||||
startPos = [0,0,0.25]
|
||||
humanoid = p.loadURDF("microtaur.urdf", startPos, useFixedBase=False)
|
||||
ob = humanoid
|
||||
jointPositions=[ 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 1.557895, 0.000000, -0.715790, -1.347363, -1.389474, 0.000000, -0.757895, -1.347364, 0.000000, 0.000000, 0.000000, 0.000000, 1.515790, 0.000000, -0.757895, -1.347364, 1.431579, 0.000000, -0.800000, -1.515786 ]
|
||||
for jointIndex in range (p.getNumJoints(ob)):
|
||||
p.resetJointState(ob,jointIndex,jointPositions[jointIndex])
|
||||
|
||||
|
||||
gravId = p.addUserDebugParameter("gravity", -10, 10, -10)
|
||||
jointIds = []
|
||||
paramIds = []
|
||||
|
||||
p.setPhysicsEngineParameter(numSolverIterations=10)
|
||||
p.changeDynamics(humanoid, -1, linearDamping=0, angularDamping=0)
|
||||
|
||||
for j in range(p.getNumJoints(humanoid)):
|
||||
p.changeDynamics(humanoid, j, linearDamping=0, angularDamping=0)
|
||||
info = p.getJointInfo(humanoid, j)
|
||||
#print(info)
|
||||
jointName = info[1]
|
||||
jointType = info[2]
|
||||
if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE):
|
||||
jointIds.append(j)
|
||||
paramIds.append(p.addUserDebugParameter(jointName.decode("utf-8"), -4, 4, jointPositions[j]))
|
||||
|
||||
p.setRealTimeSimulation(1)
|
||||
while (1):
|
||||
p.setGravity(0, 0, p.readUserDebugParameter(gravId))
|
||||
for i in range(len(paramIds)):
|
||||
c = paramIds[i]
|
||||
targetPos = p.readUserDebugParameter(c)
|
||||
p.setJointMotorControl2(humanoid, jointIds[i], p.POSITION_CONTROL, targetPos, force=5 * 240.)
|
||||
p.saveWorld("latest.py")
|
||||
time.sleep(0.01)
|
File diff suppressed because it is too large
Load Diff
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Loading…
Reference in New Issue
Block a user