Merge pull request #814 from erwincoumans/master
textured table top (no legs) + few jenga/domino blocks
This commit is contained in:
@@ -2,13 +2,11 @@
|
|||||||
<robot name="jenga.urdf">
|
<robot name="jenga.urdf">
|
||||||
<link name="baseLink">
|
<link name="baseLink">
|
||||||
<contact>
|
<contact>
|
||||||
<lateral_friction value="1.0"/>
|
<lateral_friction value=".5"/>
|
||||||
<spinning_friction value="0.5"/>
|
|
||||||
<inertia_scaling value="3.0"/>
|
|
||||||
</contact>
|
</contact>
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<mass value="1.0"/>
|
<mass value=".05"/>
|
||||||
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
|
|||||||
16
data/table/table.mtl
Normal file
16
data/table/table.mtl
Normal file
@@ -0,0 +1,16 @@
|
|||||||
|
newmtl table
|
||||||
|
Ns 10.0000
|
||||||
|
Ni 1.5000
|
||||||
|
d 1.0000
|
||||||
|
Tr 0.0000
|
||||||
|
Tf 1.0000 1.0000 1.0000
|
||||||
|
illum 2
|
||||||
|
Ka 0.0000 0.0000 0.0000
|
||||||
|
Kd 0.5880 0.5880 0.5880
|
||||||
|
Ks 0.0000 0.0000 0.0000
|
||||||
|
Ke 0.0000 0.0000 0.0000
|
||||||
|
map_Ka table.tga
|
||||||
|
map_Kd table.png
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
48
data/table/table.obj
Normal file
48
data/table/table.obj
Normal file
@@ -0,0 +1,48 @@
|
|||||||
|
# table.obj
|
||||||
|
#
|
||||||
|
|
||||||
|
o table
|
||||||
|
mtllib table.mtl
|
||||||
|
|
||||||
|
v -0.500000 -0.500000 0.500000
|
||||||
|
v 0.500000 -0.500000 0.500000
|
||||||
|
v -0.500000 0.500000 0.500000
|
||||||
|
v 0.500000 0.500000 0.500000
|
||||||
|
v -0.500000 0.500000 -0.500000
|
||||||
|
v 0.500000 0.500000 -0.500000
|
||||||
|
v -0.500000 -0.500000 -0.500000
|
||||||
|
v 0.500000 -0.500000 -0.500000
|
||||||
|
|
||||||
|
vt 0.000000 0.000000
|
||||||
|
vt 1.000000 0.000000
|
||||||
|
vt 0.000000 1.000000
|
||||||
|
vt 1.000000 1.000000
|
||||||
|
|
||||||
|
vn 0.000000 0.000000 1.000000
|
||||||
|
vn 0.000000 1.000000 0.000000
|
||||||
|
vn 0.000000 0.000000 -1.000000
|
||||||
|
vn 0.000000 -1.000000 0.000000
|
||||||
|
vn 1.000000 0.000000 0.000000
|
||||||
|
vn -1.000000 0.000000 0.000000
|
||||||
|
|
||||||
|
g table
|
||||||
|
usemtl table
|
||||||
|
s 1
|
||||||
|
f 1/1/1 2/2/1 3/3/1
|
||||||
|
f 3/3/1 2/2/1 4/4/1
|
||||||
|
s 2
|
||||||
|
f 3/1/2 4/2/2 5/3/2
|
||||||
|
f 5/3/2 4/2/2 6/4/2
|
||||||
|
s 3
|
||||||
|
f 5/4/3 6/3/3 7/2/3
|
||||||
|
f 7/2/3 6/3/3 8/1/3
|
||||||
|
s 4
|
||||||
|
f 7/1/4 8/2/4 1/3/4
|
||||||
|
f 1/3/4 8/2/4 2/4/4
|
||||||
|
s 5
|
||||||
|
f 2/1/5 8/2/5 4/3/5
|
||||||
|
f 4/3/5 8/2/5 6/4/5
|
||||||
|
s 6
|
||||||
|
f 7/1/6 1/2/6 5/3/6
|
||||||
|
f 5/3/6 1/2/6 3/4/6
|
||||||
|
|
||||||
BIN
data/table/table.png
Normal file
BIN
data/table/table.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 847 KiB |
29
data/table/table.urdf
Normal file
29
data/table/table.urdf
Normal file
@@ -0,0 +1,29 @@
|
|||||||
|
<?xml version="0.0" ?>
|
||||||
|
<robot name="table.urdf">
|
||||||
|
<link name="baseLink">
|
||||||
|
<contact>
|
||||||
|
<lateral_friction value="1.0"/>
|
||||||
|
</contact>
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<mass value=".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.6"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="table.obj" scale="1.5 1 0.05"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="white">
|
||||||
|
<color rgba="1 1 1 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0.6"/>
|
||||||
|
<geometry>
|
||||||
|
<box size="1.5 1 0.05"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
</robot>
|
||||||
|
|
||||||
@@ -3033,7 +3033,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
|||||||
|
|
||||||
for (int i = 0; i < 6; i++)
|
for (int i = 0; i < 6; i++)
|
||||||
{
|
{
|
||||||
loadUrdf("jenga/jenga.urdf", btVector3(-1-0.1*i,-0.5, .07), btQuaternion(btVector3(0,1,0),SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
loadUrdf("jenga/jenga.urdf", btVector3(-.2-0.1*i,-2., .75), btQuaternion(btVector3(0,1,0),SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||||
}
|
}
|
||||||
|
|
||||||
//loadUrdf("nao/nao.urdf", btVector3(2,5, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
//loadUrdf("nao/nao.urdf", btVector3(2,5, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||||
@@ -3110,7 +3110,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Table area
|
// Table area
|
||||||
loadUrdf("table.urdf", objectWorldTr[0].getOrigin(), objectWorldTr[0].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
loadUrdf("table/table.urdf", objectWorldTr[0].getOrigin(), objectWorldTr[0].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||||
loadUrdf("tray.urdf", objectWorldTr[1].getOrigin(), objectWorldTr[1].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
loadUrdf("tray.urdf", objectWorldTr[1].getOrigin(), objectWorldTr[1].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||||
//loadUrdf("cup_small.urdf", objectWorldTr[2].getOrigin(), objectWorldTr[2].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
//loadUrdf("cup_small.urdf", objectWorldTr[2].getOrigin(), objectWorldTr[2].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||||
//loadUrdf("pitcher_small.urdf", objectWorldTr[3].getOrigin(), objectWorldTr[3].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
//loadUrdf("pitcher_small.urdf", objectWorldTr[3].getOrigin(), objectWorldTr[3].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||||
|
|||||||
Reference in New Issue
Block a user