Merged in vrc_models (pull request #36)

Added in models from drcsim pull request #205
This commit is contained in:
Nathan Koenig 2013-05-03 17:08:16 -07:00
commit 02f581b7ba
15 changed files with 1573 additions and 16 deletions

View File

@ -13,6 +13,7 @@ string (TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER)
exec_program(date ARGS -u +%Y-%m-%-dT%H:%M:%S OUTPUT_VARIABLE CURRENT_DATE)
set (dirs
asphalt_plane
bookshelf
bowl
brick_box_3x1x3
@ -30,6 +31,7 @@ dumpster
fast_food
fire_hose_long
gas_station
grey_wall
ground_plane
hammer
hokuyo
@ -43,6 +45,7 @@ kitchen_dining
lamp_post
mailbox
monkey_wrench
mud_box
nist_elevated_floor_120
nist_fiducial_barrel
nist_maze_wall_120

View File

@ -0,0 +1,20 @@
material vrc/asphalt
{
technique
{
pass
{
ambient 0.5 0.5 0.5 1.0
diffuse 0.5 0.5 0.5 1.0
specular 0.2 0.2 0.2 1.0 12.5
texture_unit
{
texture tarmac.jpg
filtering anistropic
max_anisotropy 16
scale 0.1 0.1
}
}
}
}

Binary file not shown.

After

Width:  |  Height:  |  Size: 757 KiB

View File

@ -0,0 +1,17 @@
<?xml version="1.0"?>
<model>
<name>Asphalt Plane</name>
<version>1.0</version>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Thomas Koletschka</name>
<email>thomas.koletschka@gmail.com</email>
</author>
<description>
An asphalt textured plane.
</description>
</model>

30
asphalt_plane/model.sdf Normal file
View File

@ -0,0 +1,30 @@
<?xml version="1.0" ?>
<sdf version="1.4">
<model name="asphalt_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>20 20 .1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<cast_shadows>false</cast_shadows>
<geometry>
<box>
<size>20 20 .1</size>
</box>
</geometry>
<material>
<script>
<uri>model://asphalt_plane/materials/scripts</uri>
<uri>model://asphalt_plane/materials/textures</uri>
<name>vrc/asphalt</name>
</script>
</material>
</visual>
</link>
</model>
</sdf>

View File

@ -0,0 +1,17 @@
material vrc/grey_wall
{
receive_shadows off
technique
{
pass
{
texture_unit
{
texture grey_wall.jpg
filtering anistropic
max_anisotropy 16
scale 1 1
}
}
}
}

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.2 MiB

17
grey_wall/model.config Normal file
View File

@ -0,0 +1,17 @@
<?xml version="1.0"?>
<model>
<name>Grey Wall</name>
<version>1.0</version>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Maurice Fallon</name>
<email>mauricefallon@gmail.com</email>
</author>
<description>
A grey wall.
</description>
</model>

30
grey_wall/model.sdf Normal file
View File

@ -0,0 +1,30 @@
<?xml version="1.0" ?>
<sdf version="1.4">
<model name="grey_wall">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>7.5 0.2 2.8</size>
</box>
</geometry>
</collision>
<visual name="visual">
<cast_shadows>false</cast_shadows>
<geometry>
<box>
<size>7.5 0.2 2.8</size>
</box>
</geometry>
<material>
<script>
<uri>model://grey_wall/materials/scripts</uri>
<uri>model://grey_wall/materials/textures</uri>
<name>vrc/grey_wall</name>
</script>
</material>
</visual>
</link>
</model>
</sdf>

View File

@ -0,0 +1,19 @@
material vrc/mud
{
technique
{
pass
{
ambient 0.5 0.5 0.5 1.0
diffuse 0.5 0.5 0.5 1.0
specular 0.2 0.2 0.2 1.0 12.5
texture_unit
{
texture mud_soft_leaves.jpg
filtering anistropic
max_anisotropy 16
}
}
}
}

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.7 MiB

17
mud_box/model.config Normal file
View File

@ -0,0 +1,17 @@
<?xml version="1.0"?>
<model>
<name>Mud Box</name>
<version>1.0</version>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Thomas Koletschka</name>
<email>thomas.koletschka@gmail.com</email>
</author>
<description>
A mud textured plane.
</description>
</model>

30
mud_box/model.sdf Normal file
View File

@ -0,0 +1,30 @@
<?xml version="1.0"?>
<sdf version="1.4">
<model name="mud_box">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>8 10 0.2</size>
</box>
</geometry>
</collision>
<visual name="visual">
<cast_shadows>false</cast_shadows>
<geometry>
<box>
<size>8 10 0.2</size>
</box>
</geometry>
<material>
<script>
<uri>model://mud_box/materials/scripts</uri>
<uri>model://mud_box/materials/textures</uri>
<name>vrc/mud</name>
</script>
</material>
</visual>
</link>
</model>
</sdf>

View File

@ -13,7 +13,6 @@ material StartingPen/Floor
texture metal_ripped.jpg
filtering anistorpic
max_anisotropy 16
scale 0.1 0.1
}
}
}

File diff suppressed because it is too large Load Diff