Merged in vrc_model_improvements (pull request #34)

Use normal maps properly, updated starting pen, and construction barrel
This commit is contained in:
Nathan Koenig 2013-05-02 15:40:49 -07:00
commit beb4486394
18 changed files with 144 additions and 14 deletions

View File

@ -39,7 +39,7 @@
<color>0 0 0 1</color>
</emission>
<ambient>
<color>0.5882353 0.5882353 0.5882353 1</color>
<color>1.0 1.0 1.0 1</color>
</ambient>
<diffuse>
<texture texture="Construction_Barrel_Diffuse_tga-sampler" texcoord="CHANNEL1"/>

View File

@ -2,6 +2,17 @@
<sdf version="1.4">
<model name="Construction Barrel">
<link name="link">
<inertial>
<pose>0 0 0.4 0 0 0</pose>
<mass>500</mass>
<inertia>
<ixx>51.2096</ixx>
<iyy>51.2096</iyy>
<izz>25</izz>
<ixy>0</ixy>
<ixz>0</ixz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<mesh>

View File

@ -3,7 +3,7 @@
<model name="Fast Food">
<static>true</static>
<link name="link">
<pose>0 0 0 0 0 0</pose>
<pose>0 0 1.57965648 0 0 0</pose>
<collision name="collision">
<geometry>
<mesh>
@ -23,6 +23,10 @@
<uri>model://fast_food/materials/textures</uri>
<name>FastFood/Diffuse</name>
</script>
<shader type="normal_map_object_space">
<normal_map>FastFood_Normal.tga</normal_map>
</shader>
</material>
</visual>
</link>

View File

@ -9,6 +9,11 @@ material House_1/Diffuse
{
texture House_1_Diffuse.tga
}
rtshader_system
{
lighting_stage normal_map House_1_Normal.tga tangent_space 0
}
}
}
}

View File

@ -161,4 +161,4 @@
<scene>
<instance_visual_scene url="#MaxScene"/>
</scene>
</COLLADA>
</COLLADA>

View File

@ -22,6 +22,7 @@
<uri>model://house_1/materials/textures</uri>
<name>House_1/Diffuse</name>
</script>
<shader type="normal_map_object_space">
<normal_map>House_1_Normal.tga</normal_map>
</shader>

View File

@ -20,8 +20,13 @@
<script>
<uri>model://house_2/materials/scripts</uri>
<uri>model://house_2/materials/textures</uri>
<uri>model://house_1/materials/textures</uri>
<name>House_2/Diffuse</name>
</script>
<shader type="normal_map_object_space">
<normal_map>model://house_1/materials/textures/House_1_Normal.tga</normal_map>
</shader>
</material>
</visual>
</link>

View File

@ -105,13 +105,13 @@
<color sid="emission">0 0 0 1</color>
</emission>
<ambient>
<color sid="ambient">0 0 0 1</color>
<color sid="ambient">1 1 1 1</color>
</ambient>
<diffuse>
<color sid="diffuse">0.8 0.8 0.8 1</color>
<color sid="diffuse">1.0 1.0 1.0 1</color>
</diffuse>
<specular>
<color sid="specular">8.999999 8.999999 8.999999 1</color>
<color sid="specular">0.999999 0.999999 0.999999 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
@ -232,4 +232,4 @@
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>
</COLLADA>

View File

@ -20,8 +20,14 @@
<script>
<uri>model://house_3/materials/scripts</uri>
<uri>model://house_3/materials/textures</uri>
<uri>model://house_1/materials/textures</uri>
<name>House_3/Diffuse</name>
</script>
<shader type="normal_map_object_space">
<normal_map>model://house_1/materials/textures/House_1_Normal.tga</normal_map>
</shader>
</material>
</visual>
</link>

View File

@ -36,10 +36,10 @@
<technique sid="common">
<phong>
<emission>
<color>0 0 0 1</color>
<color>.4 .4 .4 1</color>
</emission>
<ambient>
<color>0.5882353 0.5882353 0.5882353 1</color>
<color>1.0 1.0 1.0 1</color>
</ambient>
<diffuse>
<texture texture="StopSign_Diffuse_tga-sampler" texcoord="CHANNEL1"/>
@ -116,7 +116,7 @@
<technique sid="common">
<phong>
<emission>
<color>0 0 0 1</color>
<color>.4 .4 .4 1</color>
</emission>
<ambient>
<color>0.588 0.588 0.588 1</color>

View File

@ -0,0 +1,41 @@
material StartingPen/Floor
{
receive_shadows on
technique
{
pass
{
ambient 1 1 1 1
diffuse 1 1 1 1
texture_unit
{
texture metal_ripped.jpg
filtering anistorpic
max_anisotropy 16
scale 0.1 0.1
}
}
}
}
material StartingPen/OSRF
{
receive_shadows off
technique
{
pass
{
ambient 1 1 1 1
diffuse 1 1 1 1
emissive .5 .5 .5 1.0
texture_unit
{
texture osrf.png
filtering anistorpic
max_anisotropy 16
}
}
}
}

Binary file not shown.

After

Width:  |  Height:  |  Size: 225 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 28 KiB

View File

@ -40,7 +40,7 @@
<color>0 0 0 1</color>
</emission>
<ambient>
<color>0.588 0.588 0.588 1</color>
<color>1.0 1.0 1.0 1</color>
</ambient>
<diffuse>
<texture texture="Starting_Pen_Diffuse_tga-sampler" texcoord="CHANNEL1"/>
@ -147,7 +147,7 @@
<light id="EnvironmentAmbientLight" name="EnvironmentAmbientLight">
<technique_common>
<ambient>
<color>0 0 0</color>
<color>1 1 1</color>
</ambient>
</technique_common>
</light>

View File

@ -10,6 +10,63 @@
</mesh>
</geometry>
</collision>
<collision name="collision_floor">
<pose>-3.31 7.19 0 0 0 0</pose>
<geometry>
<box>
<size>18.8 14.68 0.01</size>
</box>
</geometry>
</collision>
<visual name="visual_floor_hall">
<pose>-3.31 7.19 0 0 0 0</pose>
<geometry>
<box>
<size>18.8 14.68 0.01</size>
</box>
</geometry>
<material>
<script>
<uri>model://starting_pen/materials/scripts</uri>
<uri>model://starting_pen/materials/textures</uri>
<name>StartingPen/Floor</name>
</script>
</material>
</visual>
<visual name="visual_osrf">
<pose>-5.74 4.99 3 0 0 0</pose>
<geometry>
<box>
<size>0.01 6 1.0</size>
</box>
</geometry>
<material>
<script>
<uri>model://starting_pen/materials/scripts</uri>
<uri>model://starting_pen/materials/textures</uri>
<name>StartingPen/OSRF</name>
</script>
</material>
</visual>
<visual name="visual_osrf_2">
<pose>5.74 4.99 3 0 0 0</pose>
<geometry>
<box>
<size>0.01 6 1.0</size>
</box>
</geometry>
<material>
<script>
<uri>model://starting_pen/materials/scripts</uri>
<uri>model://starting_pen/materials/textures</uri>
<name>StartingPen/OSRF</name>
</script>
</material>
</visual>
<visual name="visual">
<geometry>
<mesh>

View File

@ -6,7 +6,7 @@
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
@ -15,6 +15,6 @@
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.5 -1.0</direction>
<direction>0.5 0.1 -0.9</direction>
</light>
</sdf>