make the motorId corresponds to that of the real minitaur. change the mass of the quadruped.urdf, change the friction of plane.urdf.

This commit is contained in:
Jie Tan
2017-02-08 17:26:36 -08:00
parent 07ba9f6629
commit 4df8b27626
4 changed files with 15 additions and 12 deletions

View File

@@ -21,7 +21,7 @@ def main(unused_args):
for i in range(1000):
a1 = math.sin(i*speed)*amplitude+1.57
a2 = math.sin(i*speed+3.14)*amplitude+1.57
joint_values = [a1, -1.57, a1, -1.57, a2, -1.57, a2, -1.57]
joint_values = [a1, 1.57, a2, 1.57, 1.57, a1, 1.57, a2]
minitaur.applyAction(joint_values)
p.stepSimulation()