update minitaur.py to use minitaur.urdf (instead of quadruped.urdf), also sort the legs in the same order as real hardware
added test urdf files for minitaur with all fixed joints, or fixed knees. added some stiffness/damping to minitaur legs (testing) tiny_obj_loader, don't crash on invalid texture coordinates btMultiBodyConstraintSolver: sweep back and forward to reduce asymmetry
This commit is contained in:
21
examples/pybullet/mylittleminitaur.py
Normal file
21
examples/pybullet/mylittleminitaur.py
Normal file
@@ -0,0 +1,21 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import math
|
||||
import sys
|
||||
sys.path.append(".")
|
||||
|
||||
from minitaur import Minitaur
|
||||
p.connect(p.GUI)
|
||||
p.setTimeOut(5)
|
||||
#p.setPhysicsEngineParameter(numSolverIterations=50)
|
||||
p.setGravity(0,0,-10)
|
||||
p.setTimeStep(0.01)
|
||||
|
||||
urdfRoot = ''
|
||||
p.loadURDF("%s/plane.urdf" % urdfRoot)
|
||||
minitaur = Minitaur(urdfRoot)
|
||||
|
||||
while (True):
|
||||
p.stepSimulation()
|
||||
time.sleep(0.01)
|
||||
|
||||
Reference in New Issue
Block a user