enable planar reflection in MinitaurGymEnv
enable follow cam in other Gym locomotion environments add testing assets for multi-material obj files -> sdf conversion. Also use ER_NO_SEGMENTATION_MASK flag for TinyRenderer/EGL plugin renderer
This commit is contained in:
122
data/threecubes/newsdf.sdf
Normal file
122
data/threecubes/newsdf.sdf
Normal file
@@ -0,0 +1,122 @@
|
|||||||
|
<sdf version='1.6'>
|
||||||
|
<world name='default'>
|
||||||
|
<gravity>0 0 -9.8</gravity>
|
||||||
|
<model name='part0.obj'>
|
||||||
|
<static>1</static>
|
||||||
|
<pose frame=''>0 0 0 0 0 0</pose>
|
||||||
|
<link name='link_d0'>
|
||||||
|
<inertial>
|
||||||
|
<mass>0</mass>
|
||||||
|
<inertia>
|
||||||
|
<ixx>0.166667</ixx>
|
||||||
|
<ixy>0</ixy>
|
||||||
|
<ixz>0</ixz>
|
||||||
|
<iyy>0.166667</iyy>
|
||||||
|
<iyz>0</iyz>
|
||||||
|
<izz>0.166667</izz>
|
||||||
|
</inertia>
|
||||||
|
</inertial>
|
||||||
|
<collision name='collision_0'>
|
||||||
|
<geometry>
|
||||||
|
<mesh>
|
||||||
|
<scale>1 1 1</scale>
|
||||||
|
<uri>part0.obj</uri>
|
||||||
|
</mesh>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<visual name='visual'>
|
||||||
|
<geometry>
|
||||||
|
<mesh>
|
||||||
|
<scale>1 1 1</scale>
|
||||||
|
<uri>part0.obj</uri>
|
||||||
|
</mesh>
|
||||||
|
</geometry>
|
||||||
|
<material>
|
||||||
|
<ambient>1 0 0 1</ambient>
|
||||||
|
<diffuse>0.000000 0.640000 0.000000 1.000000</diffuse>
|
||||||
|
<specular>0.1 0.1 0.1 1</specular>
|
||||||
|
<emissive>0 0 0 0</emissive>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
</model>
|
||||||
|
<model name='part1.obj'>
|
||||||
|
<static>1</static>
|
||||||
|
<pose frame=''>0 0 0 0 0 0</pose>
|
||||||
|
<link name='link_d1'>
|
||||||
|
<inertial>
|
||||||
|
<mass>0</mass>
|
||||||
|
<inertia>
|
||||||
|
<ixx>0.166667</ixx>
|
||||||
|
<ixy>0</ixy>
|
||||||
|
<ixz>0</ixz>
|
||||||
|
<iyy>0.166667</iyy>
|
||||||
|
<iyz>0</iyz>
|
||||||
|
<izz>0.166667</izz>
|
||||||
|
</inertia>
|
||||||
|
</inertial>
|
||||||
|
<collision name='collision_1'>
|
||||||
|
<geometry>
|
||||||
|
<mesh>
|
||||||
|
<scale>1 1 1</scale>
|
||||||
|
<uri>part1.obj</uri>
|
||||||
|
</mesh>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<visual name='visual'>
|
||||||
|
<geometry>
|
||||||
|
<mesh>
|
||||||
|
<scale>1 1 1</scale>
|
||||||
|
<uri>part1.obj</uri>
|
||||||
|
</mesh>
|
||||||
|
</geometry>
|
||||||
|
<material>
|
||||||
|
<ambient>1 0 0 1</ambient>
|
||||||
|
<diffuse>0.000000 0.000000 0.640000 1.000000</diffuse>
|
||||||
|
<specular>0.1 0.1 0.1 1</specular>
|
||||||
|
<emissive>0 0 0 0</emissive>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
</model>
|
||||||
|
<model name='part2.obj'>
|
||||||
|
<static>1</static>
|
||||||
|
<pose frame=''>0 0 0 0 0 0</pose>
|
||||||
|
<link name='link_d2'>
|
||||||
|
<inertial>
|
||||||
|
<mass>0</mass>
|
||||||
|
<inertia>
|
||||||
|
<ixx>0.166667</ixx>
|
||||||
|
<ixy>0</ixy>
|
||||||
|
<ixz>0</ixz>
|
||||||
|
<iyy>0.166667</iyy>
|
||||||
|
<iyz>0</iyz>
|
||||||
|
<izz>0.166667</izz>
|
||||||
|
</inertia>
|
||||||
|
</inertial>
|
||||||
|
<collision name='collision_2'>
|
||||||
|
<geometry>
|
||||||
|
<mesh>
|
||||||
|
<scale>1 1 1</scale>
|
||||||
|
<uri>part2.obj</uri>
|
||||||
|
</mesh>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<visual name='visual'>
|
||||||
|
<geometry>
|
||||||
|
<mesh>
|
||||||
|
<scale>1 1 1</scale>
|
||||||
|
<uri>part2.obj</uri>
|
||||||
|
</mesh>
|
||||||
|
</geometry>
|
||||||
|
<material>
|
||||||
|
<ambient>1 0 0 1</ambient>
|
||||||
|
<diffuse>0.640000 0.000000 0.000000 1.000000</diffuse>
|
||||||
|
<specular>0.1 0.1 0.1 1</specular>
|
||||||
|
<emissive>0 0 0 0</emissive>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
</model>
|
||||||
|
</world>
|
||||||
|
</sdf>
|
||||||
60
data/threecubes/part0.obj
Normal file
60
data/threecubes/part0.obj
Normal file
@@ -0,0 +1,60 @@
|
|||||||
|
# Exported using automatic converter by Erwin Coumans
|
||||||
|
mtllib three_cubes.mtl
|
||||||
|
#object Cube.001
|
||||||
|
|
||||||
|
v -4.474365 4.513344 -0.488734
|
||||||
|
v -4.474365 2.513344 -0.488735
|
||||||
|
v -4.474365 2.513344 1.511265
|
||||||
|
v -2.474365 4.513344 -0.488734
|
||||||
|
v -2.474365 2.513344 -0.488735
|
||||||
|
v -4.474365 2.513344 -0.488735
|
||||||
|
v -2.474365 4.513343 1.511266
|
||||||
|
v -2.474365 2.513344 1.511265
|
||||||
|
v -2.474365 2.513344 -0.488735
|
||||||
|
v -4.474365 4.513343 1.511266
|
||||||
|
v -4.474365 2.513344 1.511265
|
||||||
|
v -2.474365 2.513344 1.511265
|
||||||
|
v -4.474365 2.513344 -0.488735
|
||||||
|
v -2.474365 4.513343 1.511266
|
||||||
|
v -2.474365 4.513344 -0.488734
|
||||||
|
v -4.474365 4.513343 1.511266
|
||||||
|
v -4.474365 4.513344 -0.488734
|
||||||
|
v -2.474365 4.513344 -0.488734
|
||||||
|
v -2.474365 4.513343 1.511266
|
||||||
|
v -4.474365 2.513344 1.511265
|
||||||
|
usemtl Material.001
|
||||||
|
|
||||||
|
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
s off
|
||||||
|
f 1/1/1 2/2/2 3/3/3
|
||||||
|
f 4/4/4 5/5/5 6/6/6
|
||||||
|
f 7/7/7 8/8/8 9/9/9
|
||||||
|
f 10/10/10 11/11/11 12/12/12
|
||||||
|
f 13/13/13 5/5/5 12/12/12
|
||||||
|
f 10/10/10 14/14/14 15/15/15
|
||||||
|
f 16/16/16 1/1/1 3/3/3
|
||||||
|
f 17/17/17 4/4/4 6/6/6
|
||||||
|
f 18/18/18 7/7/7 9/9/9
|
||||||
|
f 19/19/19 10/10/10 12/12/12
|
||||||
|
f 20/20/20 13/13/13 12/12/12
|
||||||
|
f 17/17/17 10/10/10 15/15/15
|
||||||
60
data/threecubes/part1.obj
Normal file
60
data/threecubes/part1.obj
Normal file
@@ -0,0 +1,60 @@
|
|||||||
|
# Exported using automatic converter by Erwin Coumans
|
||||||
|
mtllib three_cubes.mtl
|
||||||
|
#object Cube.002
|
||||||
|
|
||||||
|
v -4.474365 4.513344 -3.663786
|
||||||
|
v -4.474365 2.513345 -3.663786
|
||||||
|
v -4.474365 2.513344 -1.663787
|
||||||
|
v -2.474365 4.513344 -3.663786
|
||||||
|
v -2.474365 2.513345 -3.663786
|
||||||
|
v -4.474365 2.513345 -3.663786
|
||||||
|
v -2.474365 4.513344 -1.663786
|
||||||
|
v -2.474365 2.513344 -1.663787
|
||||||
|
v -2.474365 2.513345 -3.663786
|
||||||
|
v -4.474365 4.513344 -1.663786
|
||||||
|
v -4.474365 2.513344 -1.663787
|
||||||
|
v -2.474365 2.513344 -1.663787
|
||||||
|
v -4.474365 2.513345 -3.663786
|
||||||
|
v -2.474365 4.513344 -1.663786
|
||||||
|
v -2.474365 4.513344 -3.663786
|
||||||
|
v -4.474365 4.513344 -1.663786
|
||||||
|
v -4.474365 4.513344 -3.663786
|
||||||
|
v -2.474365 4.513344 -3.663786
|
||||||
|
v -2.474365 4.513344 -1.663786
|
||||||
|
v -4.474365 2.513344 -1.663787
|
||||||
|
usemtl Material.002
|
||||||
|
|
||||||
|
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
s off
|
||||||
|
f 1/1/1 2/2/2 3/3/3
|
||||||
|
f 4/4/4 5/5/5 6/6/6
|
||||||
|
f 7/7/7 8/8/8 9/9/9
|
||||||
|
f 10/10/10 11/11/11 12/12/12
|
||||||
|
f 13/13/13 5/5/5 12/12/12
|
||||||
|
f 10/10/10 14/14/14 15/15/15
|
||||||
|
f 16/16/16 1/1/1 3/3/3
|
||||||
|
f 17/17/17 4/4/4 6/6/6
|
||||||
|
f 18/18/18 7/7/7 9/9/9
|
||||||
|
f 19/19/19 10/10/10 12/12/12
|
||||||
|
f 20/20/20 13/13/13 12/12/12
|
||||||
|
f 17/17/17 10/10/10 15/15/15
|
||||||
60
data/threecubes/part2.obj
Normal file
60
data/threecubes/part2.obj
Normal file
@@ -0,0 +1,60 @@
|
|||||||
|
# Exported using automatic converter by Erwin Coumans
|
||||||
|
mtllib three_cubes.mtl
|
||||||
|
#object Cube
|
||||||
|
|
||||||
|
v -4.474365 4.513343 2.535691
|
||||||
|
v -4.474365 2.513344 2.535691
|
||||||
|
v -4.474365 2.513343 4.535690
|
||||||
|
v -2.474365 4.513343 2.535691
|
||||||
|
v -2.474365 2.513344 2.535691
|
||||||
|
v -4.474365 2.513344 2.535691
|
||||||
|
v -2.474365 4.513343 4.535691
|
||||||
|
v -2.474365 2.513343 4.535690
|
||||||
|
v -2.474365 2.513344 2.535691
|
||||||
|
v -4.474365 4.513343 4.535691
|
||||||
|
v -4.474365 2.513343 4.535690
|
||||||
|
v -2.474365 2.513343 4.535690
|
||||||
|
v -4.474365 2.513344 2.535691
|
||||||
|
v -2.474365 4.513343 4.535691
|
||||||
|
v -2.474365 4.513343 2.535691
|
||||||
|
v -4.474365 4.513343 4.535691
|
||||||
|
v -4.474365 4.513343 2.535691
|
||||||
|
v -2.474365 4.513343 2.535691
|
||||||
|
v -2.474365 4.513343 4.535691
|
||||||
|
v -4.474365 2.513343 4.535690
|
||||||
|
usemtl Material
|
||||||
|
|
||||||
|
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
s off
|
||||||
|
f 1/1/1 2/2/2 3/3/3
|
||||||
|
f 4/4/4 5/5/5 6/6/6
|
||||||
|
f 7/7/7 8/8/8 9/9/9
|
||||||
|
f 10/10/10 11/11/11 12/12/12
|
||||||
|
f 13/13/13 5/5/5 12/12/12
|
||||||
|
f 10/10/10 14/14/14 15/15/15
|
||||||
|
f 16/16/16 1/1/1 3/3/3
|
||||||
|
f 17/17/17 4/4/4 6/6/6
|
||||||
|
f 18/18/18 7/7/7 9/9/9
|
||||||
|
f 19/19/19 10/10/10 12/12/12
|
||||||
|
f 20/20/20 13/13/13 12/12/12
|
||||||
|
f 17/17/17 10/10/10 15/15/15
|
||||||
31
data/threecubes/three_cubes.mtl
Normal file
31
data/threecubes/three_cubes.mtl
Normal file
@@ -0,0 +1,31 @@
|
|||||||
|
# Blender MTL File: 'None'
|
||||||
|
# Material Count: 3
|
||||||
|
|
||||||
|
newmtl Material
|
||||||
|
Ns 92.156863
|
||||||
|
Ka 0.000000 0.000000 0.000000
|
||||||
|
Kd 0.640000 0.000000 0.000000
|
||||||
|
Ks 0.500000 0.500000 0.500000
|
||||||
|
Ni 1.000000
|
||||||
|
d 1.000000
|
||||||
|
illum 2
|
||||||
|
|
||||||
|
|
||||||
|
newmtl Material.001
|
||||||
|
Ns 92.156863
|
||||||
|
Ka 0.000000 0.000000 0.000000
|
||||||
|
Kd 0.000000 0.640000 0.000000
|
||||||
|
Ks 0.500000 0.500000 0.500000
|
||||||
|
Ni 1.000000
|
||||||
|
d 1.000000
|
||||||
|
illum 2
|
||||||
|
|
||||||
|
newmtl Material.002
|
||||||
|
Ns 92.156863
|
||||||
|
Ka 0.000000 0.000000 0.000000
|
||||||
|
Kd 0.000000 0.000000 0.640000
|
||||||
|
Ks 0.500000 0.500000 0.500000
|
||||||
|
Ni 1.000000
|
||||||
|
d 1.000000
|
||||||
|
illum 2
|
||||||
|
|
||||||
84
data/threecubes/three_cubes.obj
Normal file
84
data/threecubes/three_cubes.obj
Normal file
@@ -0,0 +1,84 @@
|
|||||||
|
# Blender v2.71 (sub 0) OBJ File: ''
|
||||||
|
# www.blender.org
|
||||||
|
mtllib three_cubes.mtl
|
||||||
|
o Cube.001
|
||||||
|
v -4.474365 4.513343 1.511266
|
||||||
|
v -4.474365 4.513344 -0.488734
|
||||||
|
v -4.474365 2.513344 -0.488735
|
||||||
|
v -4.474365 2.513344 1.511265
|
||||||
|
v -2.474365 4.513344 -0.488734
|
||||||
|
v -2.474365 2.513344 -0.488735
|
||||||
|
v -2.474365 4.513343 1.511266
|
||||||
|
v -2.474365 2.513344 1.511265
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
usemtl Material.001
|
||||||
|
s off
|
||||||
|
f 2/1 3/2 4/3
|
||||||
|
f 5/1 6/2 3/3
|
||||||
|
f 7/1 8/2 6/3
|
||||||
|
f 1/1 4/2 8/3
|
||||||
|
f 3/1 6/2 8/3
|
||||||
|
f 1/1 7/2 5/3
|
||||||
|
f 1/4 2/1 4/3
|
||||||
|
f 2/4 5/1 3/3
|
||||||
|
f 5/4 7/1 6/3
|
||||||
|
f 7/4 1/1 8/3
|
||||||
|
f 4/4 3/1 8/3
|
||||||
|
f 2/4 1/1 5/3
|
||||||
|
o Cube.002
|
||||||
|
v -4.474365 4.513344 -1.663786
|
||||||
|
v -4.474365 4.513344 -3.663786
|
||||||
|
v -4.474365 2.513345 -3.663786
|
||||||
|
v -4.474365 2.513344 -1.663787
|
||||||
|
v -2.474365 4.513344 -3.663786
|
||||||
|
v -2.474365 2.513345 -3.663786
|
||||||
|
v -2.474365 4.513344 -1.663786
|
||||||
|
v -2.474365 2.513344 -1.663787
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
usemtl Material.002
|
||||||
|
s off
|
||||||
|
f 10/5 11/6 12/7
|
||||||
|
f 13/5 14/6 11/7
|
||||||
|
f 15/5 16/6 14/7
|
||||||
|
f 9/5 12/6 16/7
|
||||||
|
f 11/5 14/6 16/7
|
||||||
|
f 9/5 15/6 13/7
|
||||||
|
f 9/8 10/5 12/7
|
||||||
|
f 10/8 13/5 11/7
|
||||||
|
f 13/8 15/5 14/7
|
||||||
|
f 15/8 9/5 16/7
|
||||||
|
f 12/8 11/5 16/7
|
||||||
|
f 10/8 9/5 13/7
|
||||||
|
o Cube
|
||||||
|
v -4.474365 4.513343 4.535691
|
||||||
|
v -4.474365 4.513343 2.535691
|
||||||
|
v -4.474365 2.513344 2.535691
|
||||||
|
v -4.474365 2.513343 4.535690
|
||||||
|
v -2.474365 4.513343 2.535691
|
||||||
|
v -2.474365 2.513344 2.535691
|
||||||
|
v -2.474365 4.513343 4.535691
|
||||||
|
v -2.474365 2.513343 4.535690
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
usemtl Material
|
||||||
|
s off
|
||||||
|
f 18/9 19/10 20/11
|
||||||
|
f 21/9 22/10 19/11
|
||||||
|
f 23/9 24/10 22/11
|
||||||
|
f 17/9 20/10 24/11
|
||||||
|
f 19/9 22/10 24/11
|
||||||
|
f 17/9 23/10 21/11
|
||||||
|
f 17/12 18/9 20/11
|
||||||
|
f 18/12 21/9 19/11
|
||||||
|
f 21/12 23/9 22/11
|
||||||
|
f 23/12 17/9 24/11
|
||||||
|
f 20/12 19/9 24/11
|
||||||
|
f 18/12 17/9 21/11
|
||||||
8
data/threecubes/threecubes.py
Normal file
8
data/threecubes/threecubes.py
Normal file
@@ -0,0 +1,8 @@
|
|||||||
|
import pybullet as p
|
||||||
|
p.connect(p.DIRECT)
|
||||||
|
p.loadPlugin("eglRendererPlugin")
|
||||||
|
p.loadSDF("newsdf.sdf")
|
||||||
|
while (1):
|
||||||
|
p.getCameraImage(320,240, flags=p.ER_NO_SEGMENTATION_MASK)
|
||||||
|
p.stepSimulation()
|
||||||
|
|
||||||
32
data/threecubes/threecubes.urdf
Normal file
32
data/threecubes/threecubes.urdf
Normal file
@@ -0,0 +1,32 @@
|
|||||||
|
<?xml version="1.0" ?>
|
||||||
|
<robot name="cube">
|
||||||
|
<link name="baseLink">
|
||||||
|
<contact>
|
||||||
|
<lateral_friction value="1.0"/>
|
||||||
|
<rolling_friction value="0.0"/>
|
||||||
|
<contact_cfm value="0.0"/>
|
||||||
|
<contact_erp value="1.0"/>
|
||||||
|
</contact>
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<mass value="1.0"/>
|
||||||
|
<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="three_cubes.obj" scale="1 1 1"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="1 1 1 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="three_cubes.obj" scale="1 1 1"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
</robot>
|
||||||
|
|
||||||
22
data/threecubes/threecubes_org.py
Normal file
22
data/threecubes/threecubes_org.py
Normal file
@@ -0,0 +1,22 @@
|
|||||||
|
import pybullet as p
|
||||||
|
useEGL = False
|
||||||
|
useEGLGUI = False
|
||||||
|
|
||||||
|
if useEGL:
|
||||||
|
if useEGLGUI:
|
||||||
|
p.connect(p.GUI, "window_backend=2")
|
||||||
|
else:
|
||||||
|
p.connect(p.DIRECT)
|
||||||
|
p.loadPlugin("eglRendererPlugin")
|
||||||
|
else:
|
||||||
|
p.connect(p.GUI)
|
||||||
|
|
||||||
|
p.loadURDF("threecubes.urdf", flags=p.URDF_USE_MATERIAL_COLORS_FROM_MTL)
|
||||||
|
while (1):
|
||||||
|
|
||||||
|
viewmat= [0.642787516117096, -0.4393851161003113, 0.6275069713592529, 0.0, 0.766044557094574, 0.36868777871131897, -0.5265407562255859, 0.0, -0.0, 0.8191521167755127, 0.5735764503479004, 0.0, 2.384185791015625e-07, 2.384185791015625e-07, -5.000000476837158, 1.0]
|
||||||
|
projmat= [0.7499999403953552, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0, -0.02000020071864128, 0.0]
|
||||||
|
|
||||||
|
p.getCameraImage(64,64, viewMatrix=viewmat, projectionMatrix=projmat, flags=p.ER_NO_SEGMENTATION_MASK )
|
||||||
|
p.stepSimulation()
|
||||||
|
|
||||||
@@ -1311,6 +1311,7 @@ void BulletURDFImporter::convertLinkVisualShapes2(int linkIndex, int urdfIndex,
|
|||||||
UrdfLink* const* linkPtr = model.m_links.getAtIndex(urdfIndex);
|
UrdfLink* const* linkPtr = model.m_links.getAtIndex(urdfIndex);
|
||||||
if (linkPtr)
|
if (linkPtr)
|
||||||
{
|
{
|
||||||
|
m_data->m_customVisualShapesConverter->setFlags(m_data->m_flags);
|
||||||
m_data->m_customVisualShapesConverter->convertVisualShapes(linkIndex, pathPrefix, localInertiaFrame, *linkPtr, &model, colObj->getBroadphaseHandle()->getUid(), bodyUniqueId, m_data->m_fileIO);
|
m_data->m_customVisualShapesConverter->convertVisualShapes(linkIndex, pathPrefix, localInertiaFrame, *linkPtr, &model, colObj->getBroadphaseHandle()->getUid(), bodyUniqueId, m_data->m_fileIO);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -3748,6 +3748,10 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc
|
|||||||
m_data->m_pluginManager.getRenderInterface()->setProjectiveTexture(false);
|
m_data->m_pluginManager.getRenderInterface()->setProjectiveTexture(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if ((flags & ER_NO_SEGMENTATION_MASK) != 0)
|
||||||
|
{
|
||||||
|
segmentationMaskBuffer = 0;
|
||||||
|
}
|
||||||
|
|
||||||
m_data->m_pluginManager.getRenderInterface()->copyCameraImageData(pixelRGBA, numRequestedPixels,
|
m_data->m_pluginManager.getRenderInterface()->copyCameraImageData(pixelRGBA, numRequestedPixels,
|
||||||
depthBuffer, numRequestedPixels,
|
depthBuffer, numRequestedPixels,
|
||||||
|
|||||||
@@ -820,7 +820,7 @@ enum eURDF_Flags
|
|||||||
URDF_USE_SELF_COLLISION_INCLUDE_PARENT = 8192,
|
URDF_USE_SELF_COLLISION_INCLUDE_PARENT = 8192,
|
||||||
URDF_PARSE_SENSORS = 16384,
|
URDF_PARSE_SENSORS = 16384,
|
||||||
URDF_USE_MATERIAL_COLORS_FROM_MTL = 32768,
|
URDF_USE_MATERIAL_COLORS_FROM_MTL = 32768,
|
||||||
URDF_USE_MATERIAL_TRANSPARANCY_FROM_MTL = 64738,
|
URDF_USE_MATERIAL_TRANSPARANCY_FROM_MTL = 65536,
|
||||||
};
|
};
|
||||||
|
|
||||||
enum eUrdfGeomTypes //sync with UrdfParser UrdfGeomTypes
|
enum eUrdfGeomTypes //sync with UrdfParser UrdfGeomTypes
|
||||||
|
|||||||
@@ -270,13 +270,14 @@ void EGLRendererVisualShapeConverter::setLightSpecularCoeff(float specularCoeff)
|
|||||||
}
|
}
|
||||||
|
|
||||||
///todo: merge into single file with TinyRendererVisualShapeConverter
|
///todo: merge into single file with TinyRendererVisualShapeConverter
|
||||||
static void convertURDFToVisualShape2(const UrdfShape* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<MyTexture3>& texturesOut, b3VisualShapeData& visualShapeOut, struct CommonFileIOInterface* fileIO)
|
static void convertURDFToVisualShape2(const UrdfShape* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<MyTexture3>& texturesOut, b3VisualShapeData& visualShapeOut, struct CommonFileIOInterface* fileIO, int flags)
|
||||||
{
|
{
|
||||||
visualShapeOut.m_visualGeometryType = visual->m_geometry.m_type;
|
visualShapeOut.m_visualGeometryType = visual->m_geometry.m_type;
|
||||||
visualShapeOut.m_dimensions[0] = 0;
|
visualShapeOut.m_dimensions[0] = 0;
|
||||||
visualShapeOut.m_dimensions[1] = 0;
|
visualShapeOut.m_dimensions[1] = 0;
|
||||||
visualShapeOut.m_dimensions[2] = 0;
|
visualShapeOut.m_dimensions[2] = 0;
|
||||||
memset(visualShapeOut.m_meshAssetFileName, 0, sizeof(visualShapeOut.m_meshAssetFileName));
|
memset(visualShapeOut.m_meshAssetFileName, 0, sizeof(visualShapeOut.m_meshAssetFileName));
|
||||||
|
#if 0
|
||||||
if (visual->m_geometry.m_hasLocalMaterial)
|
if (visual->m_geometry.m_hasLocalMaterial)
|
||||||
{
|
{
|
||||||
visualShapeOut.m_rgbaColor[0] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[0];
|
visualShapeOut.m_rgbaColor[0] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[0];
|
||||||
@@ -284,6 +285,7 @@ static void convertURDFToVisualShape2(const UrdfShape* visual, const char* urdfP
|
|||||||
visualShapeOut.m_rgbaColor[2] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[2];
|
visualShapeOut.m_rgbaColor[2] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[2];
|
||||||
visualShapeOut.m_rgbaColor[3] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[3];
|
visualShapeOut.m_rgbaColor[3] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[3];
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
GLInstanceGraphicsShape* glmesh = 0;
|
GLInstanceGraphicsShape* glmesh = 0;
|
||||||
|
|
||||||
@@ -412,6 +414,23 @@ static void convertURDFToVisualShape2(const UrdfShape* visual, const char* urdfP
|
|||||||
b3ImportMeshData meshData;
|
b3ImportMeshData meshData;
|
||||||
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData, fileIO))
|
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData, fileIO))
|
||||||
{
|
{
|
||||||
|
if (flags&URDF_USE_MATERIAL_COLORS_FROM_MTL)
|
||||||
|
{
|
||||||
|
if (meshData.m_flags & B3_IMPORT_MESH_HAS_RGBA_COLOR)
|
||||||
|
{
|
||||||
|
visualShapeOut.m_rgbaColor[0] = meshData.m_rgbaColor[0];
|
||||||
|
visualShapeOut.m_rgbaColor[1] = meshData.m_rgbaColor[1];
|
||||||
|
visualShapeOut.m_rgbaColor[2] = meshData.m_rgbaColor[2];
|
||||||
|
|
||||||
|
if (flags&URDF_USE_MATERIAL_TRANSPARANCY_FROM_MTL)
|
||||||
|
{
|
||||||
|
visualShapeOut.m_rgbaColor[3] = meshData.m_rgbaColor[3];
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
visualShapeOut.m_rgbaColor[3] = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
if (meshData.m_textureImage1)
|
if (meshData.m_textureImage1)
|
||||||
{
|
{
|
||||||
MyTexture3 texData;
|
MyTexture3 texData;
|
||||||
@@ -752,7 +771,7 @@ void EGLRendererVisualShapeConverter::convertVisualShapes(
|
|||||||
visualShape.m_rgbaColor[3] = rgbaColor[3];
|
visualShape.m_rgbaColor[3] = rgbaColor[3];
|
||||||
{
|
{
|
||||||
B3_PROFILE("convertURDFToVisualShape2");
|
B3_PROFILE("convertURDFToVisualShape2");
|
||||||
convertURDFToVisualShape2(vis, pathPrefix, localInertiaFrame.inverse() * childTrans, vertices, indices, textures, visualShape, fileIO);
|
convertURDFToVisualShape2(vis, pathPrefix, localInertiaFrame.inverse() * childTrans, vertices, indices, textures, visualShape, fileIO, m_data->m_flags);
|
||||||
}
|
}
|
||||||
m_data->m_visualShapes.push_back(visualShape);
|
m_data->m_visualShapes.push_back(visualShape);
|
||||||
|
|
||||||
|
|||||||
@@ -182,13 +182,14 @@ void TinyRendererVisualShapeConverter::setLightSpecularCoeff(float specularCoeff
|
|||||||
m_data->m_hasLightSpecularCoeff = true;
|
m_data->m_hasLightSpecularCoeff = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<MyTexture2>& texturesOut, b3VisualShapeData& visualShapeOut, struct CommonFileIOInterface* fileIO)
|
static void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<MyTexture2>& texturesOut, b3VisualShapeData& visualShapeOut, struct CommonFileIOInterface* fileIO, int flags)
|
||||||
{
|
{
|
||||||
visualShapeOut.m_visualGeometryType = visual->m_geometry.m_type;
|
visualShapeOut.m_visualGeometryType = visual->m_geometry.m_type;
|
||||||
visualShapeOut.m_dimensions[0] = 0;
|
visualShapeOut.m_dimensions[0] = 0;
|
||||||
visualShapeOut.m_dimensions[1] = 0;
|
visualShapeOut.m_dimensions[1] = 0;
|
||||||
visualShapeOut.m_dimensions[2] = 0;
|
visualShapeOut.m_dimensions[2] = 0;
|
||||||
memset(visualShapeOut.m_meshAssetFileName, 0, sizeof(visualShapeOut.m_meshAssetFileName));
|
memset(visualShapeOut.m_meshAssetFileName, 0, sizeof(visualShapeOut.m_meshAssetFileName));
|
||||||
|
#if 0
|
||||||
if (visual->m_geometry.m_hasLocalMaterial)
|
if (visual->m_geometry.m_hasLocalMaterial)
|
||||||
{
|
{
|
||||||
visualShapeOut.m_rgbaColor[0] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[0];
|
visualShapeOut.m_rgbaColor[0] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[0];
|
||||||
@@ -196,6 +197,7 @@ static void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPa
|
|||||||
visualShapeOut.m_rgbaColor[2] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[2];
|
visualShapeOut.m_rgbaColor[2] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[2];
|
||||||
visualShapeOut.m_rgbaColor[3] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[3];
|
visualShapeOut.m_rgbaColor[3] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[3];
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
GLInstanceGraphicsShape* glmesh = 0;
|
GLInstanceGraphicsShape* glmesh = 0;
|
||||||
|
|
||||||
@@ -322,8 +324,26 @@ static void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPa
|
|||||||
{
|
{
|
||||||
//glmesh = LoadMeshFromObj(fullPath,visualPathPrefix);
|
//glmesh = LoadMeshFromObj(fullPath,visualPathPrefix);
|
||||||
b3ImportMeshData meshData;
|
b3ImportMeshData meshData;
|
||||||
|
|
||||||
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData, fileIO))
|
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData, fileIO))
|
||||||
{
|
{
|
||||||
|
if (flags&URDF_USE_MATERIAL_COLORS_FROM_MTL)
|
||||||
|
{
|
||||||
|
if (meshData.m_flags & B3_IMPORT_MESH_HAS_RGBA_COLOR)
|
||||||
|
{
|
||||||
|
visualShapeOut.m_rgbaColor[0] = meshData.m_rgbaColor[0];
|
||||||
|
visualShapeOut.m_rgbaColor[1] = meshData.m_rgbaColor[1];
|
||||||
|
visualShapeOut.m_rgbaColor[2] = meshData.m_rgbaColor[2];
|
||||||
|
|
||||||
|
if (flags&URDF_USE_MATERIAL_TRANSPARANCY_FROM_MTL)
|
||||||
|
{
|
||||||
|
visualShapeOut.m_rgbaColor[3] = meshData.m_rgbaColor[3];
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
visualShapeOut.m_rgbaColor[3] = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
if (meshData.m_textureImage1)
|
if (meshData.m_textureImage1)
|
||||||
{
|
{
|
||||||
MyTexture2 texData;
|
MyTexture2 texData;
|
||||||
@@ -665,9 +685,14 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
|||||||
|
|
||||||
{
|
{
|
||||||
B3_PROFILE("convertURDFToVisualShape");
|
B3_PROFILE("convertURDFToVisualShape");
|
||||||
convertURDFToVisualShape(vis, pathPrefix, localInertiaFrame.inverse() * childTrans, vertices, indices, textures, visualShape, fileIO);
|
convertURDFToVisualShape(vis, pathPrefix, localInertiaFrame.inverse() * childTrans, vertices, indices, textures, visualShape, fileIO, m_data->m_flags);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
rgbaColor[0] = visualShape.m_rgbaColor[0];
|
||||||
|
rgbaColor[1] = visualShape.m_rgbaColor[1];
|
||||||
|
rgbaColor[2] = visualShape.m_rgbaColor[2];
|
||||||
|
rgbaColor[3] = visualShape.m_rgbaColor[3];
|
||||||
|
|
||||||
if (vertices.size() && indices.size())
|
if (vertices.size() && indices.size())
|
||||||
{
|
{
|
||||||
TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer, m_data->m_depthBuffer, &m_data->m_shadowBuffer, &m_data->m_segmentationMaskBuffer, bodyUniqueId, linkIndex);
|
TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer, m_data->m_depthBuffer, &m_data->m_shadowBuffer, &m_data->m_segmentationMaskBuffer, bodyUniqueId, linkIndex);
|
||||||
|
|||||||
@@ -111,6 +111,16 @@ class MJCFBaseBulletEnv(gym.Env):
|
|||||||
# backwards compatibility for gym >= v0.9.x
|
# backwards compatibility for gym >= v0.9.x
|
||||||
# for extension of this class.
|
# for extension of this class.
|
||||||
def step(self, *args, **kwargs):
|
def step(self, *args, **kwargs):
|
||||||
|
if self.isRender:
|
||||||
|
base_pos=[0,0,0]
|
||||||
|
if (hasattr(self,'robot')):
|
||||||
|
if (hasattr(self.robot,'body_xyz')):
|
||||||
|
base_pos = self.robot.body_xyz
|
||||||
|
# Keep the previous orientation of the camera set by the user.
|
||||||
|
#[yaw, pitch, dist] = self._p.getDebugVisualizerCamera()[8:11]
|
||||||
|
self._p.resetDebugVisualizerCamera(3,0,0, base_pos)
|
||||||
|
|
||||||
|
|
||||||
return self._step(*args, **kwargs)
|
return self._step(*args, **kwargs)
|
||||||
|
|
||||||
if parse_version(gym.__version__)>=parse_version('0.9.6'):
|
if parse_version(gym.__version__)>=parse_version('0.9.6'):
|
||||||
|
|||||||
@@ -271,7 +271,7 @@ class MinitaurGymEnv(gym.Env):
|
|||||||
"%s/plane.urdf" % self._urdf_root)
|
"%s/plane.urdf" % self._urdf_root)
|
||||||
if (self._reflection):
|
if (self._reflection):
|
||||||
self._pybullet_client.changeVisualShape(self._ground_id,-1,rgbaColor=[1,1,1,0.8])
|
self._pybullet_client.changeVisualShape(self._ground_id,-1,rgbaColor=[1,1,1,0.8])
|
||||||
#self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION,1)
|
self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION,self._ground_id)
|
||||||
self._pybullet_client.setGravity(0, 0, -10)
|
self._pybullet_client.setGravity(0, 0, -10)
|
||||||
acc_motor = self._accurate_motor_model_enabled
|
acc_motor = self._accurate_motor_model_enabled
|
||||||
motor_protect = self._motor_overheat_protection
|
motor_protect = self._motor_overheat_protection
|
||||||
|
|||||||
Reference in New Issue
Block a user