mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 13:20:07 +00:00
Merge remote-tracking branch 'bp/master'
This commit is contained in:
commit
08b83c3cd8
21
data/dinnerware/dinnerware.mtl
Normal file
21
data/dinnerware/dinnerware.mtl
Normal file
@ -0,0 +1,21 @@
|
|||||||
|
newmtl porcelain
|
||||||
|
Ka 0.000000 0.000000 0.000000
|
||||||
|
Kd 1.000000 1.000000 1.000000
|
||||||
|
Ks 0.200000 0.200000 0.200000
|
||||||
|
d 1.000000
|
||||||
|
illum 2
|
||||||
|
Ns 0.000000
|
||||||
|
|
||||||
|
newmtl solid_color
|
||||||
|
Ka 0.000000 0.000000 0.000000
|
||||||
|
Kd 1.000000 1.000000 1.000000
|
||||||
|
Ks 0.200000 0.200000 0.200000
|
||||||
|
d 1.000000
|
||||||
|
illum 2
|
||||||
|
Ns 0.000000
|
||||||
|
|
||||||
|
newmtl pan_tefal
|
||||||
|
Ka 0.000000 0.000000 0.000000
|
||||||
|
Kd 0.609804 0.494118 0.486275
|
||||||
|
Ks 0.330000 0.330000 0.330000
|
||||||
|
map_Kd pan_tefal.jpg
|
252
data/dinnerware/generate.py
Normal file
252
data/dinnerware/generate.py
Normal file
@ -0,0 +1,252 @@
|
|||||||
|
from __future__ import print_function
|
||||||
|
import numpy as np
|
||||||
|
|
||||||
|
class Obj:
|
||||||
|
def __init__(self, fn):
|
||||||
|
self.ind_v = 0
|
||||||
|
self.ind_vt = 0
|
||||||
|
self.ind_vn = 0
|
||||||
|
self.fn = fn
|
||||||
|
self.out = open(fn + ".tmp", "w")
|
||||||
|
self.out.write("mtllib dinnerware.mtl\n")
|
||||||
|
def __del__(self):
|
||||||
|
self.out.close()
|
||||||
|
import shutil
|
||||||
|
shutil.move(self.fn + ".tmp", self.fn)
|
||||||
|
def push_v(self, v):
|
||||||
|
self.out.write("v %f %f %f\n" % (v[0],v[1],v[2]))
|
||||||
|
self.ind_v += 1
|
||||||
|
return self.ind_v
|
||||||
|
def push_vt(self, vt):
|
||||||
|
self.out.write("vt %f %f\n" % (vt[0],vt[1]))
|
||||||
|
self.ind_vt += 1
|
||||||
|
return self.ind_vt
|
||||||
|
def push_vn(self, vn):
|
||||||
|
vn /= np.linalg.norm(vn)
|
||||||
|
self.out.write("vn %f %f %f\n" % (vn[0],vn[1],vn[2]))
|
||||||
|
self.ind_vn += 1
|
||||||
|
return self.ind_vn
|
||||||
|
|
||||||
|
|
||||||
|
def convex_hull(points, vind, nind, tind, obj):
|
||||||
|
"super ineffective"
|
||||||
|
cnt = len(points)
|
||||||
|
for a in range(cnt):
|
||||||
|
for b in range(a+1,cnt):
|
||||||
|
for c in range(b+1,cnt):
|
||||||
|
vec1 = points[a] - points[b]
|
||||||
|
vec2 = points[a] - points[c]
|
||||||
|
n = np.cross(vec1, vec2)
|
||||||
|
n /= np.linalg.norm(n)
|
||||||
|
C = np.dot(n, points[a])
|
||||||
|
inner = np.inner(n, points)
|
||||||
|
pos = (inner <= C+0.0001).all()
|
||||||
|
neg = (inner >= C-0.0001).all()
|
||||||
|
if not pos and not neg: continue
|
||||||
|
obj.out.write("f %i//%i %i//%i %i//%i\n" % (
|
||||||
|
(vind[a], nind[a], vind[b], nind[b], vind[c], nind[c])
|
||||||
|
if (inner - C).sum() < 0 else
|
||||||
|
(vind[a], nind[a], vind[c], nind[c], vind[b], nind[b]) ) )
|
||||||
|
#obj.out.write("f %i/%i/%i %i/%i/%i %i/%i/%i\n" % (
|
||||||
|
# (vind[a], tind[a], nind[a], vind[b], tind[b], nind[b], vind[c], tind[c], nind[c])
|
||||||
|
# if (inner - C).sum() < 0 else
|
||||||
|
# (vind[a], tind[a], nind[a], vind[c], tind[c], nind[c], vind[b], tind[b], nind[b]) ) )
|
||||||
|
|
||||||
|
def test_convex_hull():
|
||||||
|
obj = Obj("convex_test.obj")
|
||||||
|
vlist = np.random.uniform( low=-0.1, high=+0.1, size=(100,3) )
|
||||||
|
nlist = vlist.copy()
|
||||||
|
tlist = np.random.uniform( low=0, high=+1, size=(100,2) )
|
||||||
|
vind = [obj.push_v(xyz) for xyz in vlist]
|
||||||
|
nind = [obj.push_vn(xyz) for xyz in nlist]
|
||||||
|
tind = [obj.push_vt(uv) for uv in tlist]
|
||||||
|
convex_hull(vlist, vind, nind, tind, obj)
|
||||||
|
|
||||||
|
class Contour:
|
||||||
|
def __init__(self):
|
||||||
|
self.vprev_vind = None
|
||||||
|
|
||||||
|
def f(self, obj, vlist_vind, vlist_tind, vlist_nind):
|
||||||
|
cnt = len(vlist_vind)
|
||||||
|
for i1 in range(cnt):
|
||||||
|
i2 = i1-1
|
||||||
|
obj.out.write("f %i/%i/%i %i/%i/%i %i/%i/%i\n" % (
|
||||||
|
vlist_vind[i2], vlist_tind[i2], vlist_nind[i2],
|
||||||
|
vlist_vind[i1], vlist_tind[i1], vlist_nind[i1],
|
||||||
|
self.vprev_vind[i1], self.vprev_tind[i1], self.vprev_nind[i1],
|
||||||
|
) )
|
||||||
|
obj.out.write("f %i/%i/%i %i/%i/%i %i/%i/%i\n" % (
|
||||||
|
vlist_vind[i2], vlist_tind[i2], vlist_nind[i2],
|
||||||
|
self.vprev_vind[i1], self.vprev_tind[i1], self.vprev_nind[i1],
|
||||||
|
self.vprev_vind[i2], self.vprev_tind[i2], self.vprev_nind[i2],
|
||||||
|
) )
|
||||||
|
|
||||||
|
def belt(self, obj, vlist, nlist, tlist):
|
||||||
|
vlist_vind = [obj.push_v(xyz) for xyz in vlist]
|
||||||
|
vlist_tind = [obj.push_vt(xyz) for xyz in tlist]
|
||||||
|
vlist_nind = [obj.push_vn(xyz) for xyz in nlist]
|
||||||
|
if self.vprev_vind:
|
||||||
|
self.f(obj, vlist_vind, vlist_tind, vlist_nind)
|
||||||
|
else:
|
||||||
|
self.first_vind = vlist_vind
|
||||||
|
self.first_tind = vlist_tind
|
||||||
|
self.first_nind = vlist_nind
|
||||||
|
self.vprev_vind = vlist_vind
|
||||||
|
self.vprev_tind = vlist_tind
|
||||||
|
self.vprev_nind = vlist_nind
|
||||||
|
|
||||||
|
def finish(self, obj):
|
||||||
|
self.f(obj, self.first_vind, self.first_tind, self.first_nind)
|
||||||
|
|
||||||
|
def test_contour():
|
||||||
|
RAD1 = 2.0
|
||||||
|
RAD2 = 1.5
|
||||||
|
obj = Obj("torus.obj")
|
||||||
|
obj.out.write("usemtl porcelain\n")
|
||||||
|
contour = Contour()
|
||||||
|
for step in range(100):
|
||||||
|
angle = step/100.0*2*np.pi
|
||||||
|
belt_v = []
|
||||||
|
belt_n = []
|
||||||
|
belt_t = []
|
||||||
|
for b in range(50):
|
||||||
|
beta = b/50.0*2*np.pi
|
||||||
|
r = RAD2*np.cos(beta) + RAD1
|
||||||
|
z = RAD2*np.sin(beta)
|
||||||
|
belt_v.append( np.array( [
|
||||||
|
np.cos(angle)*r,
|
||||||
|
np.sin(angle)*r,
|
||||||
|
z] ) )
|
||||||
|
belt_n.append( np.array( [
|
||||||
|
np.cos(angle)*np.cos(beta),
|
||||||
|
np.sin(angle)*np.cos(beta),
|
||||||
|
np.sin(beta)] ) )
|
||||||
|
belt_t.append( (0,0) )
|
||||||
|
contour.belt(obj, belt_v, belt_n, belt_t)
|
||||||
|
contour.finish(obj)
|
||||||
|
|
||||||
|
#test_convex_hull()
|
||||||
|
#test_contour()
|
||||||
|
|
||||||
|
class RotationFigureParams:
|
||||||
|
pass
|
||||||
|
|
||||||
|
def generate_plate(p, obj, collision_prefix):
|
||||||
|
contour = Contour()
|
||||||
|
belt_vlist_3d_prev = None
|
||||||
|
|
||||||
|
for step in range(p.N_VIZ+1):
|
||||||
|
angle = step/float(p.N_VIZ)*2*np.pi
|
||||||
|
|
||||||
|
if step % p.COLLISION_EVERY == 0:
|
||||||
|
vlist_3d = []
|
||||||
|
for x,y in p.belt_simple:
|
||||||
|
vlist_3d.append( [
|
||||||
|
np.cos(angle)*x*1.06,
|
||||||
|
np.sin(angle)*x*1.06,
|
||||||
|
y
|
||||||
|
] )
|
||||||
|
if belt_vlist_3d_prev:
|
||||||
|
obj2 = Obj(collision_prefix % (step / p.COLLISION_EVERY))
|
||||||
|
obj2.out.write("usemtl pan_tefal\n")
|
||||||
|
vlist = np.array( vlist_3d + belt_vlist_3d_prev )
|
||||||
|
vlist[len(vlist_3d):] *= 1.01 # break points on one plane
|
||||||
|
vlist[0,0:2] += 0.01*vlist[len(vlist_3d),0:2]
|
||||||
|
vlist[len(vlist_3d),0:2] += 0.01*vlist[0,0:2]
|
||||||
|
nlist = np.random.uniform( low=-1, high=+1, size=vlist.shape )
|
||||||
|
tlist = np.random.uniform( low=0, high=+1, size=(len(vlist),2) )
|
||||||
|
vind = [obj2.push_v(xyz) for xyz in vlist]
|
||||||
|
nind = [obj2.push_vn(xyz) for xyz in nlist]
|
||||||
|
convex_hull(vlist, vind, nind, None, obj2)
|
||||||
|
belt_vlist_3d_prev = vlist_3d
|
||||||
|
if step==p.N_VIZ: break
|
||||||
|
|
||||||
|
belt_v = []
|
||||||
|
belt_n = []
|
||||||
|
belt_t = []
|
||||||
|
for x,y,nx,ny in p.belt:
|
||||||
|
belt_v.append( np.array( [
|
||||||
|
np.cos(angle)*x,
|
||||||
|
np.sin(angle)*x,
|
||||||
|
y
|
||||||
|
] ) )
|
||||||
|
belt_n.append( np.array( [
|
||||||
|
np.cos(angle)*nx,
|
||||||
|
np.sin(angle)*nx,
|
||||||
|
ny
|
||||||
|
] ) )
|
||||||
|
if ny-nx >= 0:
|
||||||
|
belt_t.append( (
|
||||||
|
127.0/512 + np.cos(angle)*x/p.RAD_HIGH*105/512,
|
||||||
|
(512-135.0)/512 + np.sin(angle)*x/p.RAD_HIGH*105/512) )
|
||||||
|
else:
|
||||||
|
belt_t.append( (
|
||||||
|
382.0/512 + np.cos(angle)*x/p.RAD_HIGH*125/512,
|
||||||
|
(512-380.0)/512 + np.sin(angle)*x/p.RAD_HIGH*125/512) )
|
||||||
|
contour.belt(obj, belt_v, belt_n, belt_t)
|
||||||
|
|
||||||
|
contour.finish(obj)
|
||||||
|
|
||||||
|
def tefal():
|
||||||
|
p = RotationFigureParams()
|
||||||
|
p.RAD_LOW = 0.240/2
|
||||||
|
p.RAD_HIGH = 0.255/2
|
||||||
|
p.H = 0.075
|
||||||
|
p.THICK = 0.005
|
||||||
|
p.N_VIZ = 30
|
||||||
|
p.COLLISION_EVERY = 5
|
||||||
|
p.belt = [
|
||||||
|
(p.RAD_HIGH-p.THICK, p.H, -1,0), # x y norm
|
||||||
|
(p.RAD_HIGH , p.H, 0,1),
|
||||||
|
(p.RAD_HIGH+p.THICK, p.H, +1,0),
|
||||||
|
(p.RAD_LOW+p.THICK, p.THICK, +1,0),
|
||||||
|
(p.RAD_LOW , 0, 0,-1),
|
||||||
|
( 0, 0, 0,-1),
|
||||||
|
( 0, p.THICK, 0,1),
|
||||||
|
(p.RAD_LOW-p.THICK, p.THICK, 0,1),
|
||||||
|
(p.RAD_LOW-p.THICK, 3*p.THICK,-1,0),
|
||||||
|
]
|
||||||
|
p.belt.reverse()
|
||||||
|
p.belt_simple = [
|
||||||
|
(p.RAD_HIGH-p.THICK, p.H),
|
||||||
|
(p.RAD_HIGH+p.THICK, p.H),
|
||||||
|
(p.RAD_LOW , 0),
|
||||||
|
(p.RAD_LOW-p.THICK , 0)
|
||||||
|
]
|
||||||
|
obj = Obj("pan_tefal.obj")
|
||||||
|
obj.out.write("usemtl pan_tefal\n")
|
||||||
|
generate_plate(p, obj, "pan_tefal-collision%02i.obj")
|
||||||
|
|
||||||
|
def plate():
|
||||||
|
p = RotationFigureParams()
|
||||||
|
p.RAD_LOW = 0.110/2
|
||||||
|
p.RAD_HIGH = 0.190/2
|
||||||
|
p.H = 0.060
|
||||||
|
p.THICK = 0.003
|
||||||
|
p.N_VIZ = 30
|
||||||
|
p.COLLISION_EVERY = 5
|
||||||
|
p.belt = [
|
||||||
|
(p.RAD_HIGH-p.THICK, p.H, -0.9,0.5), # x y norm
|
||||||
|
(p.RAD_HIGH , p.H, 0,1),
|
||||||
|
(p.RAD_HIGH+p.THICK, p.H, +1,0),
|
||||||
|
(p.RAD_LOW+p.THICK, p.THICK, +1,0),
|
||||||
|
(p.RAD_LOW , 0, 0,-1),
|
||||||
|
( 0, 0, 0,-1),
|
||||||
|
( 0, p.THICK, 0,1),
|
||||||
|
(p.RAD_LOW-3*p.THICK, p.THICK, 0,1),
|
||||||
|
(p.RAD_LOW-p.THICK, 3*p.THICK,-0.5,1.0),
|
||||||
|
]
|
||||||
|
p.belt.reverse()
|
||||||
|
p.belt_simple = [
|
||||||
|
(p.RAD_HIGH-p.THICK, p.H),
|
||||||
|
(p.RAD_HIGH+p.THICK, p.H),
|
||||||
|
(p.RAD_LOW , 0),
|
||||||
|
(p.RAD_LOW-p.THICK , 0)
|
||||||
|
]
|
||||||
|
obj = Obj("plate.obj")
|
||||||
|
obj.out.write("usemtl solid_color\n")
|
||||||
|
generate_plate(p, obj, "plate-collision%02i.obj")
|
||||||
|
|
||||||
|
plate()
|
||||||
|
|
||||||
|
|
36
data/dinnerware/pan_tefal-collision01.obj
Normal file
36
data/dinnerware/pan_tefal-collision01.obj
Normal file
@ -0,0 +1,36 @@
|
|||||||
|
mtllib dinnerware.mtl
|
||||||
|
usemtl pan_tefal
|
||||||
|
v 0.066236 0.112453 0.075000
|
||||||
|
v 0.070225 0.121633 0.075000
|
||||||
|
v 0.063600 0.110158 0.000000
|
||||||
|
v 0.060950 0.105568 0.000000
|
||||||
|
v 0.131811 0.001125 0.075750
|
||||||
|
v 0.141855 0.000000 0.075750
|
||||||
|
v 0.128472 0.000000 0.000000
|
||||||
|
v 0.123119 0.000000 0.000000
|
||||||
|
vn 0.166577 -0.705775 0.688573
|
||||||
|
vn -0.727212 0.200240 0.656556
|
||||||
|
vn 0.637357 -0.756451 -0.146827
|
||||||
|
vn -0.340753 -0.711716 0.614286
|
||||||
|
vn 0.122979 0.860640 0.494141
|
||||||
|
vn 0.770289 -0.238643 0.591358
|
||||||
|
vn -0.635571 -0.120420 0.762594
|
||||||
|
vn -0.070367 0.649517 -0.757084
|
||||||
|
f 1//1 2//2 4//4
|
||||||
|
f 1//1 5//5 2//2
|
||||||
|
f 1//1 6//6 2//2
|
||||||
|
f 1//1 4//4 5//5
|
||||||
|
f 1//1 4//4 8//8
|
||||||
|
f 1//1 5//5 6//6
|
||||||
|
f 1//1 8//8 5//5
|
||||||
|
f 2//2 3//3 4//4
|
||||||
|
f 2//2 7//7 3//3
|
||||||
|
f 2//2 5//5 6//6
|
||||||
|
f 2//2 6//6 7//7
|
||||||
|
f 3//3 7//7 4//4
|
||||||
|
f 3//3 8//8 4//4
|
||||||
|
f 3//3 7//7 8//8
|
||||||
|
f 4//4 8//8 5//5
|
||||||
|
f 4//4 7//7 8//8
|
||||||
|
f 5//5 8//8 6//6
|
||||||
|
f 6//6 8//8 7//7
|
36
data/dinnerware/pan_tefal-collision02.obj
Normal file
36
data/dinnerware/pan_tefal-collision02.obj
Normal file
@ -0,0 +1,36 @@
|
|||||||
|
mtllib dinnerware.mtl
|
||||||
|
usemtl pan_tefal
|
||||||
|
v -0.064269 0.113589 0.075000
|
||||||
|
v -0.070225 0.121633 0.075000
|
||||||
|
v -0.063600 0.110158 0.000000
|
||||||
|
v -0.060950 0.105568 0.000000
|
||||||
|
v 0.064932 0.114714 0.075750
|
||||||
|
v 0.070927 0.122850 0.075750
|
||||||
|
v 0.064236 0.111260 0.000000
|
||||||
|
v 0.061560 0.106624 0.000000
|
||||||
|
vn -0.693799 -0.019731 0.719898
|
||||||
|
vn -0.782132 -0.410509 0.468776
|
||||||
|
vn 0.057085 0.837906 0.542821
|
||||||
|
vn 0.549444 0.695908 -0.462410
|
||||||
|
vn -0.488898 0.761278 -0.425951
|
||||||
|
vn 0.527121 -0.833525 0.165465
|
||||||
|
vn 0.764499 0.413217 0.494766
|
||||||
|
vn -0.190845 -0.280421 -0.940714
|
||||||
|
f 1//1 2//2 4//4
|
||||||
|
f 1//1 5//5 2//2
|
||||||
|
f 1//1 6//6 2//2
|
||||||
|
f 1//1 4//4 5//5
|
||||||
|
f 1//1 4//4 8//8
|
||||||
|
f 1//1 5//5 6//6
|
||||||
|
f 1//1 8//8 5//5
|
||||||
|
f 2//2 3//3 4//4
|
||||||
|
f 2//2 7//7 3//3
|
||||||
|
f 2//2 5//5 6//6
|
||||||
|
f 2//2 6//6 7//7
|
||||||
|
f 3//3 7//7 4//4
|
||||||
|
f 3//3 8//8 4//4
|
||||||
|
f 3//3 7//7 8//8
|
||||||
|
f 4//4 8//8 5//5
|
||||||
|
f 4//4 7//7 8//8
|
||||||
|
f 5//5 8//8 6//6
|
||||||
|
f 6//6 8//8 7//7
|
36
data/dinnerware/pan_tefal-collision03.obj
Normal file
36
data/dinnerware/pan_tefal-collision03.obj
Normal file
@ -0,0 +1,36 @@
|
|||||||
|
mtllib dinnerware.mtl
|
||||||
|
usemtl pan_tefal
|
||||||
|
v -0.130506 0.001136 0.075000
|
||||||
|
v -0.140450 0.000000 0.075000
|
||||||
|
v -0.127200 0.000000 0.000000
|
||||||
|
v -0.121900 0.000000 0.000000
|
||||||
|
v -0.066879 0.113589 0.075750
|
||||||
|
v -0.070927 0.122850 0.075750
|
||||||
|
v -0.064236 0.111260 0.000000
|
||||||
|
v -0.061559 0.106624 0.000000
|
||||||
|
vn -0.005755 -0.840864 -0.541216
|
||||||
|
vn -0.393829 -0.423425 0.815849
|
||||||
|
vn 0.855454 0.357218 -0.374959
|
||||||
|
vn -0.535483 -0.042852 -0.843458
|
||||||
|
vn 0.593436 -0.341238 0.728966
|
||||||
|
vn -0.684303 -0.643863 0.342301
|
||||||
|
vn -0.543719 -0.112982 0.831628
|
||||||
|
vn -0.432322 -0.733068 0.525080
|
||||||
|
f 1//1 2//2 4//4
|
||||||
|
f 1//1 5//5 2//2
|
||||||
|
f 1//1 6//6 2//2
|
||||||
|
f 1//1 4//4 5//5
|
||||||
|
f 1//1 4//4 8//8
|
||||||
|
f 1//1 5//5 6//6
|
||||||
|
f 1//1 8//8 5//5
|
||||||
|
f 2//2 3//3 4//4
|
||||||
|
f 2//2 7//7 3//3
|
||||||
|
f 2//2 5//5 6//6
|
||||||
|
f 2//2 6//6 7//7
|
||||||
|
f 3//3 7//7 4//4
|
||||||
|
f 3//3 8//8 4//4
|
||||||
|
f 3//3 7//7 8//8
|
||||||
|
f 4//4 8//8 5//5
|
||||||
|
f 4//4 7//7 8//8
|
||||||
|
f 5//5 8//8 6//6
|
||||||
|
f 6//6 8//8 7//7
|
36
data/dinnerware/pan_tefal-collision04.obj
Normal file
36
data/dinnerware/pan_tefal-collision04.obj
Normal file
@ -0,0 +1,36 @@
|
|||||||
|
mtllib dinnerware.mtl
|
||||||
|
usemtl pan_tefal
|
||||||
|
v -0.066236 -0.112453 0.075000
|
||||||
|
v -0.070225 -0.121633 0.075000
|
||||||
|
v -0.063600 -0.110158 0.000000
|
||||||
|
v -0.060950 -0.105568 0.000000
|
||||||
|
v -0.131811 -0.001125 0.075750
|
||||||
|
v -0.141855 0.000000 0.075750
|
||||||
|
v -0.128472 0.000000 0.000000
|
||||||
|
v -0.123119 0.000000 0.000000
|
||||||
|
vn -0.706733 -0.191066 0.681192
|
||||||
|
vn 0.444900 -0.691793 0.568758
|
||||||
|
vn 0.088502 0.609907 0.787515
|
||||||
|
vn -0.441942 -0.815296 0.374139
|
||||||
|
vn -0.595750 0.064829 0.800549
|
||||||
|
vn -0.683770 -0.459760 -0.566639
|
||||||
|
vn -0.132581 -0.607583 0.783112
|
||||||
|
vn -0.220415 -0.970551 0.097201
|
||||||
|
f 1//1 2//2 4//4
|
||||||
|
f 1//1 5//5 2//2
|
||||||
|
f 1//1 6//6 2//2
|
||||||
|
f 1//1 4//4 5//5
|
||||||
|
f 1//1 4//4 8//8
|
||||||
|
f 1//1 5//5 6//6
|
||||||
|
f 1//1 8//8 5//5
|
||||||
|
f 2//2 3//3 4//4
|
||||||
|
f 2//2 7//7 3//3
|
||||||
|
f 2//2 5//5 6//6
|
||||||
|
f 2//2 6//6 7//7
|
||||||
|
f 3//3 7//7 4//4
|
||||||
|
f 3//3 8//8 4//4
|
||||||
|
f 3//3 7//7 8//8
|
||||||
|
f 4//4 8//8 5//5
|
||||||
|
f 4//4 7//7 8//8
|
||||||
|
f 5//5 8//8 6//6
|
||||||
|
f 6//6 8//8 7//7
|
36
data/dinnerware/pan_tefal-collision05.obj
Normal file
36
data/dinnerware/pan_tefal-collision05.obj
Normal file
@ -0,0 +1,36 @@
|
|||||||
|
mtllib dinnerware.mtl
|
||||||
|
usemtl pan_tefal
|
||||||
|
v 0.064269 -0.113589 0.075000
|
||||||
|
v 0.070225 -0.121633 0.075000
|
||||||
|
v 0.063600 -0.110158 0.000000
|
||||||
|
v 0.060950 -0.105568 0.000000
|
||||||
|
v -0.064932 -0.114714 0.075750
|
||||||
|
v -0.070927 -0.122850 0.075750
|
||||||
|
v -0.064236 -0.111260 0.000000
|
||||||
|
v -0.061560 -0.106624 0.000000
|
||||||
|
vn 0.337731 -0.812635 0.474934
|
||||||
|
vn -0.151863 -0.910103 0.385551
|
||||||
|
vn -0.786673 0.591186 -0.177887
|
||||||
|
vn 0.661692 0.712532 0.233371
|
||||||
|
vn -0.904799 0.159708 -0.394757
|
||||||
|
vn 0.641963 -0.023667 -0.766370
|
||||||
|
vn -0.472889 -0.878846 0.063294
|
||||||
|
vn 0.722857 0.565784 -0.396694
|
||||||
|
f 1//1 2//2 4//4
|
||||||
|
f 1//1 5//5 2//2
|
||||||
|
f 1//1 6//6 2//2
|
||||||
|
f 1//1 4//4 5//5
|
||||||
|
f 1//1 4//4 8//8
|
||||||
|
f 1//1 5//5 6//6
|
||||||
|
f 1//1 8//8 5//5
|
||||||
|
f 2//2 3//3 4//4
|
||||||
|
f 2//2 7//7 3//3
|
||||||
|
f 2//2 5//5 6//6
|
||||||
|
f 2//2 6//6 7//7
|
||||||
|
f 3//3 7//7 4//4
|
||||||
|
f 3//3 8//8 4//4
|
||||||
|
f 3//3 7//7 8//8
|
||||||
|
f 4//4 8//8 5//5
|
||||||
|
f 4//4 7//7 8//8
|
||||||
|
f 5//5 8//8 6//6
|
||||||
|
f 6//6 8//8 7//7
|
36
data/dinnerware/pan_tefal-collision06.obj
Normal file
36
data/dinnerware/pan_tefal-collision06.obj
Normal file
@ -0,0 +1,36 @@
|
|||||||
|
mtllib dinnerware.mtl
|
||||||
|
usemtl pan_tefal
|
||||||
|
v 0.130506 -0.001136 0.075000
|
||||||
|
v 0.140450 -0.000000 0.075000
|
||||||
|
v 0.127200 -0.000000 0.000000
|
||||||
|
v 0.121900 -0.000000 0.000000
|
||||||
|
v 0.066879 -0.113589 0.075750
|
||||||
|
v 0.070927 -0.122850 0.075750
|
||||||
|
v 0.064236 -0.111260 0.000000
|
||||||
|
v 0.061560 -0.106624 0.000000
|
||||||
|
vn -0.793944 -0.586742 -0.159329
|
||||||
|
vn 0.466324 0.641735 -0.608867
|
||||||
|
vn -0.911102 -0.220305 -0.348365
|
||||||
|
vn -0.616532 -0.769008 0.168863
|
||||||
|
vn -0.642390 0.561142 0.521973
|
||||||
|
vn -0.527497 0.482140 0.699491
|
||||||
|
vn -0.264570 0.491705 0.829596
|
||||||
|
vn -0.595670 0.662065 0.454804
|
||||||
|
f 1//1 2//2 4//4
|
||||||
|
f 1//1 5//5 2//2
|
||||||
|
f 1//1 6//6 2//2
|
||||||
|
f 1//1 4//4 5//5
|
||||||
|
f 1//1 4//4 8//8
|
||||||
|
f 1//1 5//5 6//6
|
||||||
|
f 1//1 8//8 5//5
|
||||||
|
f 2//2 3//3 4//4
|
||||||
|
f 2//2 7//7 3//3
|
||||||
|
f 2//2 5//5 6//6
|
||||||
|
f 2//2 6//6 7//7
|
||||||
|
f 3//3 7//7 4//4
|
||||||
|
f 3//3 8//8 4//4
|
||||||
|
f 3//3 7//7 8//8
|
||||||
|
f 4//4 8//8 5//5
|
||||||
|
f 4//4 7//7 8//8
|
||||||
|
f 5//5 8//8 6//6
|
||||||
|
f 6//6 8//8 7//7
|
BIN
data/dinnerware/pan_tefal.jpg
Normal file
BIN
data/dinnerware/pan_tefal.jpg
Normal file
Binary file not shown.
After Width: | Height: | Size: 40 KiB |
1352
data/dinnerware/pan_tefal.obj
Normal file
1352
data/dinnerware/pan_tefal.obj
Normal file
File diff suppressed because it is too large
Load Diff
84
data/dinnerware/pan_tefal.urdf
Normal file
84
data/dinnerware/pan_tefal.urdf
Normal file
@ -0,0 +1,84 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot name="cube">
|
||||||
|
<!-- Frying pan model, Copyright (c) 2016 Oleg Klimov -->
|
||||||
|
<!-- LICENSE: CC-SA -->
|
||||||
|
<link name="cube">
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="pan_tefal.obj"/>
|
||||||
|
</geometry>
|
||||||
|
</visual>
|
||||||
|
<visual> <!-- handle -->
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.011" length="0.185"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 1.4 0" xyz="0.22 0 0.07"/>
|
||||||
|
<material name="stainless">
|
||||||
|
<color rgba="0.3 0.3 .3 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
|
||||||
|
<collision> <!-- handle -->
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.011" length="0.185"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 1.4 0" xyz="0.22 0 0.07"/>
|
||||||
|
</collision>
|
||||||
|
<collision> <!-- bottom -->
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.12" length="0.01"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0.005"/>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="pan_tefal-collision01.obj"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="pan_tefal-collision02.obj"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="pan_tefal-collision03.obj"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="pan_tefal-collision04.obj"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="pan_tefal-collision05.obj"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="pan_tefal-collision06.obj"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<inertial>
|
||||||
|
<mass value="2."/> <!-- mr^2 = 0.5*0.12^2 = 0.0072 for Z axis, lighter along other axis -->
|
||||||
|
<inertia ixx="0.005" iyy="0.005" izz="0.0072"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
</robot>
|
||||||
|
|
34
data/dinnerware/plate-collision01.obj
Normal file
34
data/dinnerware/plate-collision01.obj
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
mtllib dinnerware.mtl
|
||||||
|
usemtl pan_tefal
|
||||||
|
v 0.049745 0.084455 0.060000
|
||||||
|
v 0.051940 0.089963 0.060000
|
||||||
|
v 0.029150 0.050489 0.000000
|
||||||
|
v 0.027560 0.047735 0.000000
|
||||||
|
v 0.098993 0.000845 0.060600
|
||||||
|
v 0.104919 0.000000 0.060600
|
||||||
|
v 0.058883 0.000000 0.000000
|
||||||
|
v 0.055671 0.000000 0.000000
|
||||||
|
vn -0.962255 -0.069189 0.263208
|
||||||
|
vn 0.888900 -0.266051 0.372926
|
||||||
|
vn -0.704117 -0.151605 -0.693711
|
||||||
|
vn -0.096471 -0.952673 -0.288284
|
||||||
|
vn 0.353510 0.535276 0.767144
|
||||||
|
vn 0.049583 0.551162 -0.832924
|
||||||
|
vn -0.080990 0.081838 -0.993349
|
||||||
|
vn 0.250326 0.614585 -0.748080
|
||||||
|
f 1//1 2//2 4//4
|
||||||
|
f 1//1 5//5 2//2
|
||||||
|
f 1//1 6//6 2//2
|
||||||
|
f 1//1 4//4 5//5
|
||||||
|
f 1//1 5//5 6//6
|
||||||
|
f 2//2 3//3 4//4
|
||||||
|
f 2//2 7//7 3//3
|
||||||
|
f 2//2 5//5 6//6
|
||||||
|
f 2//2 6//6 7//7
|
||||||
|
f 3//3 7//7 4//4
|
||||||
|
f 3//3 8//8 4//4
|
||||||
|
f 3//3 7//7 8//8
|
||||||
|
f 4//4 8//8 5//5
|
||||||
|
f 4//4 7//7 8//8
|
||||||
|
f 5//5 8//8 6//6
|
||||||
|
f 6//6 8//8 7//7
|
34
data/dinnerware/plate-collision02.obj
Normal file
34
data/dinnerware/plate-collision02.obj
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
mtllib dinnerware.mtl
|
||||||
|
usemtl pan_tefal
|
||||||
|
v -0.048268 0.085308 0.060000
|
||||||
|
v -0.051940 0.089963 0.060000
|
||||||
|
v -0.029150 0.050489 0.000000
|
||||||
|
v -0.027560 0.047735 0.000000
|
||||||
|
v 0.048765 0.086152 0.060600
|
||||||
|
v 0.052459 0.090862 0.060600
|
||||||
|
v 0.029442 0.050994 0.000000
|
||||||
|
v 0.027836 0.048213 0.000000
|
||||||
|
vn -0.471567 -0.127056 -0.872629
|
||||||
|
vn 0.616670 0.313448 -0.722127
|
||||||
|
vn 0.434277 -0.589449 -0.681141
|
||||||
|
vn -0.696898 0.673938 -0.245235
|
||||||
|
vn -0.964280 0.142499 -0.223288
|
||||||
|
vn -0.118273 0.245678 -0.962109
|
||||||
|
vn 0.333505 0.310546 -0.890133
|
||||||
|
vn 0.592935 -0.751851 -0.288355
|
||||||
|
f 1//1 2//2 4//4
|
||||||
|
f 1//1 5//5 2//2
|
||||||
|
f 1//1 6//6 2//2
|
||||||
|
f 1//1 4//4 5//5
|
||||||
|
f 1//1 5//5 6//6
|
||||||
|
f 2//2 3//3 4//4
|
||||||
|
f 2//2 7//7 3//3
|
||||||
|
f 2//2 5//5 6//6
|
||||||
|
f 2//2 6//6 7//7
|
||||||
|
f 3//3 7//7 4//4
|
||||||
|
f 3//3 8//8 4//4
|
||||||
|
f 3//3 7//7 8//8
|
||||||
|
f 4//4 8//8 5//5
|
||||||
|
f 4//4 7//7 8//8
|
||||||
|
f 5//5 8//8 6//6
|
||||||
|
f 6//6 8//8 7//7
|
34
data/dinnerware/plate-collision03.obj
Normal file
34
data/dinnerware/plate-collision03.obj
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
mtllib dinnerware.mtl
|
||||||
|
usemtl pan_tefal
|
||||||
|
v -0.098012 0.000853 0.060000
|
||||||
|
v -0.103880 0.000000 0.060000
|
||||||
|
v -0.058300 0.000000 0.000000
|
||||||
|
v -0.055120 0.000000 0.000000
|
||||||
|
v -0.050228 0.085308 0.060600
|
||||||
|
v -0.052459 0.090862 0.060600
|
||||||
|
v -0.029441 0.050994 0.000000
|
||||||
|
v -0.027836 0.048213 0.000000
|
||||||
|
vn -0.570326 0.565919 -0.595368
|
||||||
|
vn -0.987481 0.122113 -0.099846
|
||||||
|
vn 0.256877 0.509622 0.821157
|
||||||
|
vn -0.149510 -0.272737 0.950401
|
||||||
|
vn 0.250981 -0.885212 0.391675
|
||||||
|
vn 0.623883 0.757497 -0.192269
|
||||||
|
vn 0.116527 -0.876135 -0.467769
|
||||||
|
vn -0.474452 0.562082 -0.677466
|
||||||
|
f 1//1 2//2 4//4
|
||||||
|
f 1//1 5//5 2//2
|
||||||
|
f 1//1 6//6 2//2
|
||||||
|
f 1//1 4//4 5//5
|
||||||
|
f 1//1 5//5 6//6
|
||||||
|
f 2//2 3//3 4//4
|
||||||
|
f 2//2 7//7 3//3
|
||||||
|
f 2//2 5//5 6//6
|
||||||
|
f 2//2 6//6 7//7
|
||||||
|
f 3//3 7//7 4//4
|
||||||
|
f 3//3 8//8 4//4
|
||||||
|
f 3//3 7//7 8//8
|
||||||
|
f 4//4 8//8 5//5
|
||||||
|
f 4//4 7//7 8//8
|
||||||
|
f 5//5 8//8 6//6
|
||||||
|
f 6//6 8//8 7//7
|
34
data/dinnerware/plate-collision04.obj
Normal file
34
data/dinnerware/plate-collision04.obj
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
mtllib dinnerware.mtl
|
||||||
|
usemtl pan_tefal
|
||||||
|
v -0.049745 -0.084455 0.060000
|
||||||
|
v -0.051940 -0.089963 0.060000
|
||||||
|
v -0.029150 -0.050489 0.000000
|
||||||
|
v -0.027560 -0.047735 0.000000
|
||||||
|
v -0.098993 -0.000845 0.060600
|
||||||
|
v -0.104919 0.000000 0.060600
|
||||||
|
v -0.058883 0.000000 0.000000
|
||||||
|
v -0.055671 0.000000 0.000000
|
||||||
|
vn -0.454516 0.625342 -0.634321
|
||||||
|
vn -0.518286 -0.578386 0.629959
|
||||||
|
vn -0.173259 0.226757 -0.958417
|
||||||
|
vn -0.247982 -0.510538 -0.823320
|
||||||
|
vn -0.417030 0.446958 0.791400
|
||||||
|
vn -0.004783 -0.717725 -0.696310
|
||||||
|
vn 0.273713 0.103751 0.956199
|
||||||
|
vn 0.429490 0.309534 -0.848367
|
||||||
|
f 1//1 2//2 4//4
|
||||||
|
f 1//1 5//5 2//2
|
||||||
|
f 1//1 6//6 2//2
|
||||||
|
f 1//1 4//4 5//5
|
||||||
|
f 1//1 5//5 6//6
|
||||||
|
f 2//2 3//3 4//4
|
||||||
|
f 2//2 7//7 3//3
|
||||||
|
f 2//2 5//5 6//6
|
||||||
|
f 2//2 6//6 7//7
|
||||||
|
f 3//3 7//7 4//4
|
||||||
|
f 3//3 8//8 4//4
|
||||||
|
f 3//3 7//7 8//8
|
||||||
|
f 4//4 8//8 5//5
|
||||||
|
f 4//4 7//7 8//8
|
||||||
|
f 5//5 8//8 6//6
|
||||||
|
f 6//6 8//8 7//7
|
34
data/dinnerware/plate-collision05.obj
Normal file
34
data/dinnerware/plate-collision05.obj
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
mtllib dinnerware.mtl
|
||||||
|
usemtl pan_tefal
|
||||||
|
v 0.048268 -0.085308 0.060000
|
||||||
|
v 0.051940 -0.089963 0.060000
|
||||||
|
v 0.029150 -0.050489 0.000000
|
||||||
|
v 0.027560 -0.047735 0.000000
|
||||||
|
v -0.048765 -0.086152 0.060600
|
||||||
|
v -0.052459 -0.090862 0.060600
|
||||||
|
v -0.029442 -0.050994 0.000000
|
||||||
|
v -0.027836 -0.048213 0.000000
|
||||||
|
vn 0.404852 0.441710 0.800617
|
||||||
|
vn -0.882548 -0.029017 0.469326
|
||||||
|
vn 0.182767 0.981935 0.048984
|
||||||
|
vn -0.768458 0.392626 -0.505290
|
||||||
|
vn 0.592713 0.805382 -0.007215
|
||||||
|
vn 0.400028 0.869068 0.291031
|
||||||
|
vn -0.642772 0.691166 0.330355
|
||||||
|
vn 0.104670 0.652086 -0.750885
|
||||||
|
f 1//1 2//2 4//4
|
||||||
|
f 1//1 5//5 2//2
|
||||||
|
f 1//1 6//6 2//2
|
||||||
|
f 1//1 4//4 5//5
|
||||||
|
f 1//1 5//5 6//6
|
||||||
|
f 2//2 3//3 4//4
|
||||||
|
f 2//2 7//7 3//3
|
||||||
|
f 2//2 5//5 6//6
|
||||||
|
f 2//2 6//6 7//7
|
||||||
|
f 3//3 7//7 4//4
|
||||||
|
f 3//3 8//8 4//4
|
||||||
|
f 3//3 7//7 8//8
|
||||||
|
f 4//4 8//8 5//5
|
||||||
|
f 4//4 7//7 8//8
|
||||||
|
f 5//5 8//8 6//6
|
||||||
|
f 6//6 8//8 7//7
|
34
data/dinnerware/plate-collision06.obj
Normal file
34
data/dinnerware/plate-collision06.obj
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
mtllib dinnerware.mtl
|
||||||
|
usemtl pan_tefal
|
||||||
|
v 0.098012 -0.000853 0.060000
|
||||||
|
v 0.103880 -0.000000 0.060000
|
||||||
|
v 0.058300 -0.000000 0.000000
|
||||||
|
v 0.055120 -0.000000 0.000000
|
||||||
|
v 0.050228 -0.085308 0.060600
|
||||||
|
v 0.052459 -0.090862 0.060600
|
||||||
|
v 0.029442 -0.050994 0.000000
|
||||||
|
v 0.027836 -0.048213 0.000000
|
||||||
|
vn 0.692885 0.707963 -0.136739
|
||||||
|
vn 0.408978 0.907585 0.095006
|
||||||
|
vn -0.212286 -0.468709 0.857465
|
||||||
|
vn 0.297056 -0.618852 0.727172
|
||||||
|
vn 0.708170 0.492350 -0.506050
|
||||||
|
vn 0.745762 -0.289343 -0.600100
|
||||||
|
vn 0.808951 0.000863 -0.587876
|
||||||
|
vn 0.926527 0.350079 -0.137811
|
||||||
|
f 1//1 2//2 4//4
|
||||||
|
f 1//1 5//5 2//2
|
||||||
|
f 1//1 6//6 2//2
|
||||||
|
f 1//1 4//4 5//5
|
||||||
|
f 1//1 5//5 6//6
|
||||||
|
f 2//2 3//3 4//4
|
||||||
|
f 2//2 7//7 3//3
|
||||||
|
f 2//2 5//5 6//6
|
||||||
|
f 2//2 6//6 7//7
|
||||||
|
f 3//3 7//7 4//4
|
||||||
|
f 3//3 8//8 4//4
|
||||||
|
f 3//3 7//7 8//8
|
||||||
|
f 4//4 8//8 5//5
|
||||||
|
f 4//4 7//7 8//8
|
||||||
|
f 5//5 8//8 6//6
|
||||||
|
f 6//6 8//8 7//7
|
1352
data/dinnerware/plate.obj
Normal file
1352
data/dinnerware/plate.obj
Normal file
File diff suppressed because it is too large
Load Diff
69
data/dinnerware/plate.urdf
Normal file
69
data/dinnerware/plate.urdf
Normal file
@ -0,0 +1,69 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot name="cube">
|
||||||
|
<!-- Frying pan model, Copyright (c) 2016 Oleg Klimov -->
|
||||||
|
<!-- LICENSE: CC-SA -->
|
||||||
|
<link name="cube">
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="plate.obj"/>
|
||||||
|
</geometry>
|
||||||
|
</visual>
|
||||||
|
|
||||||
|
<collision> <!-- bottom -->
|
||||||
|
<geometry>
|
||||||
|
<cylinder radius="0.05" length="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0.0025"/>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="plate-collision01.obj"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="plate-collision02.obj"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="plate-collision03.obj"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="plate-collision04.obj"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="plate-collision05.obj"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="plate-collision06.obj"/>
|
||||||
|
</geometry>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<inertial>
|
||||||
|
<mass value="0.5"/> <!-- mr^2 = 0.5*0.12^2 = 0.0072 for Z axis, lighter along other axis -->
|
||||||
|
<inertia ixx="0.005" iyy="0.005" izz="0.0072"/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
</robot>
|
||||||
|
|
30
data/sphere_1cm.urdf
Normal file
30
data/sphere_1cm.urdf
Normal file
@ -0,0 +1,30 @@
|
|||||||
|
<?xml version="0.0" ?>
|
||||||
|
<robot name="urdf_robot">
|
||||||
|
<link name="base_link">
|
||||||
|
<contact>
|
||||||
|
<rolling_friction value="0.0001"/>
|
||||||
|
<spinning_friction value="0.0001"/>
|
||||||
|
</contact>
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<mass value=".1"/>
|
||||||
|
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="textured_sphere_smooth.obj" scale="0.005 0.005 0.005"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="1 1 1 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<sphere radius="0.005"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
</robot>
|
||||||
|
|
25
examples/pybullet/manyspheres.py
Normal file
25
examples/pybullet/manyspheres.py
Normal file
@ -0,0 +1,25 @@
|
|||||||
|
import pybullet as p
|
||||||
|
import time
|
||||||
|
|
||||||
|
p.connect(p.GUI)
|
||||||
|
p.loadURDF("plane.urdf",useMaximalCoordinates=True)
|
||||||
|
p.loadURDF("tray/traybox.urdf",useMaximalCoordinates=True)
|
||||||
|
|
||||||
|
gravXid = p.addUserDebugParameter("gravityX",-10,10,0)
|
||||||
|
gravYid = p.addUserDebugParameter("gravityY",-10,10,0)
|
||||||
|
gravZid = p.addUserDebugParameter("gravityZ",-10,10,0)
|
||||||
|
p.setPhysicsEngineParameter(numSolverIterations=10)
|
||||||
|
|
||||||
|
for i in range (10):
|
||||||
|
for j in range (10):
|
||||||
|
for k in range (5):
|
||||||
|
ob = p.loadURDF("sphere_1cm.urdf",[0.02*i,0.02*j,0.2+0.02*k],useMaximalCoordinates=True)
|
||||||
|
p.setGravity(0,0,-10)
|
||||||
|
p.setRealTimeSimulation(1)
|
||||||
|
while True:
|
||||||
|
gravX = p.readUserDebugParameter(gravXid)
|
||||||
|
gravY = p.readUserDebugParameter(gravYid)
|
||||||
|
gravZ = p.readUserDebugParameter(gravZid)
|
||||||
|
p.setGravity(gravX,gravY,gravZ)
|
||||||
|
time.sleep(1)
|
||||||
|
|
Loading…
Reference in New Issue
Block a user