improve getAABB.py drawing

This commit is contained in:
Erwin Coumans
2017-06-16 19:11:35 -07:00
parent 23b155a2b4
commit 5ea4da87d7

View File

@@ -1,50 +1,51 @@
import pybullet as p import pybullet as p
p.connect(p.GUI) draw=1
printtext = 0
if (draw):
p.connect(p.GUI)
else:
p.connect(p.DIRECT)
r2d2 = p.loadURDF("r2d2.urdf") r2d2 = p.loadURDF("r2d2.urdf")
def drawAABB(aabb):
aabb = p.getAABB(r2d2)
aabbMin = aabb[0]
aabbMax = aabb[1]
f = [aabbMin[0],aabbMin[1],aabbMin[2]]
t = [aabbMax[0],aabbMin[1],aabbMin[2]]
p.addUserDebugLine(f,t,[1,1,1])
f = [aabbMin[0],aabbMin[1],aabbMin[2]]
t = [aabbMin[0],aabbMax[1],aabbMin[2]]
p.addUserDebugLine(f,t,[1,1,1])
f = [aabbMin[0],aabbMin[1],aabbMin[2]]
t = [aabbMin[0],aabbMin[1],aabbMax[2]]
p.addUserDebugLine(f,t,[1,1,1])
f = [aabbMax[0],aabbMax[1],aabbMax[2]]
t = [aabbMin[0],aabbMax[1],aabbMax[2]]
p.addUserDebugLine(f,t,[1,1,1])
f = [aabbMax[0],aabbMax[1],aabbMax[2]]
t = [aabbMax[0],aabbMin[1],aabbMax[2]]
p.addUserDebugLine(f,t,[1,1,1])
f = [aabbMax[0],aabbMax[1],aabbMax[2]]
t = [aabbMax[0],aabbMax[1],aabbMin[2]]
p.addUserDebugLine(f,t,[1,1,1])
for i in range (p.getNumJoints(r2d2)):
aabb = p.getAABB(r2d2,i)
aabbMin = aabb[0]
aabbMax = aabb[1]
f = [aabbMin[0],aabbMin[1],aabbMin[2]] f = [aabbMin[0],aabbMin[1],aabbMin[2]]
t = [aabbMax[0],aabbMin[1],aabbMin[2]] t = [aabbMax[0],aabbMin[1],aabbMin[2]]
p.addUserDebugLine(f,t,[1,1,1]) p.addUserDebugLine(f,t,[1,0,0])
f = [aabbMin[0],aabbMin[1],aabbMin[2]] f = [aabbMin[0],aabbMin[1],aabbMin[2]]
t = [aabbMin[0],aabbMax[1],aabbMin[2]] t = [aabbMin[0],aabbMax[1],aabbMin[2]]
p.addUserDebugLine(f,t,[1,1,1]) p.addUserDebugLine(f,t,[0,1,0])
f = [aabbMin[0],aabbMin[1],aabbMin[2]] f = [aabbMin[0],aabbMin[1],aabbMin[2]]
t = [aabbMin[0],aabbMin[1],aabbMax[2]] t = [aabbMin[0],aabbMin[1],aabbMax[2]]
p.addUserDebugLine(f,t,[1,1,1]) p.addUserDebugLine(f,t,[0,0,1])
f = [aabbMax[0],aabbMax[1],aabbMax[2]] f = [aabbMin[0],aabbMin[1],aabbMax[2]]
t = [aabbMin[0],aabbMax[1],aabbMax[2]] t = [aabbMin[0],aabbMax[1],aabbMax[2]]
p.addUserDebugLine(f,t,[1,1,1]) p.addUserDebugLine(f,t,[1,1,1])
f = [aabbMin[0],aabbMin[1],aabbMax[2]]
t = [aabbMax[0],aabbMin[1],aabbMax[2]]
p.addUserDebugLine(f,t,[1,1,1])
f = [aabbMax[0],aabbMin[1],aabbMin[2]]
t = [aabbMax[0],aabbMin[1],aabbMax[2]]
p.addUserDebugLine(f,t,[1,1,1])
f = [aabbMax[0],aabbMin[1],aabbMin[2]]
t = [aabbMax[0],aabbMax[1],aabbMin[2]]
p.addUserDebugLine(f,t,[1,1,1])
f = [aabbMax[0],aabbMax[1],aabbMin[2]]
t = [aabbMin[0],aabbMax[1],aabbMin[2]]
p.addUserDebugLine(f,t,[1,1,1])
f = [aabbMin[0],aabbMax[1],aabbMin[2]]
t = [aabbMin[0],aabbMax[1],aabbMax[2]]
p.addUserDebugLine(f,t,[1,1,1])
f = [aabbMax[0],aabbMax[1],aabbMax[2]]
t = [aabbMin[0],aabbMax[1],aabbMax[2]]
p.addUserDebugLine(f,t,[1.0,0.5,0.5])
f = [aabbMax[0],aabbMax[1],aabbMax[2]] f = [aabbMax[0],aabbMax[1],aabbMax[2]]
t = [aabbMax[0],aabbMin[1],aabbMax[2]] t = [aabbMax[0],aabbMin[1],aabbMax[2]]
p.addUserDebugLine(f,t,[1,1,1]) p.addUserDebugLine(f,t,[1,1,1])
@@ -52,5 +53,25 @@ for i in range (p.getNumJoints(r2d2)):
t = [aabbMax[0],aabbMax[1],aabbMin[2]] t = [aabbMax[0],aabbMax[1],aabbMin[2]]
p.addUserDebugLine(f,t,[1,1,1]) p.addUserDebugLine(f,t,[1,1,1])
aabb = p.getAABB(r2d2)
aabbMin = aabb[0]
aabbMax = aabb[1]
if (printtext):
print(aabbMin)
print(aabbMax)
if (draw==1):
drawAABB(aabb)
for i in range (p.getNumJoints(r2d2)):
aabb = p.getAABB(r2d2,i)
aabbMin = aabb[0]
aabbMax = aabb[1]
if (printtext):
print(aabbMin)
print(aabbMax)
if (draw==1):
drawAABB(aabb)
while(1): while(1):
a=0 a=0