init
This commit is contained in:
15
checkerboard_plane/checkerboard_plane.sdf
Normal file
15
checkerboard_plane/checkerboard_plane.sdf
Normal file
@@ -0,0 +1,15 @@
|
||||
<?xml version='1.0'?>
|
||||
<sdf version="1.6">
|
||||
<model name="checkerboard_plane">
|
||||
<static>true</static>
|
||||
<link name="link">
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://checkerboard_plane/meshes/checkerboard_plane.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
</sdf>
|
BIN
checkerboard_plane/materials/textures/checker.png
Normal file
BIN
checkerboard_plane/materials/textures/checker.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 17 KiB |
126
checkerboard_plane/meshes/checkerboard_plane.dae
Normal file
126
checkerboard_plane/meshes/checkerboard_plane.dae
Normal file
@@ -0,0 +1,126 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
|
||||
<asset>
|
||||
<contributor>
|
||||
<author>Blender User</author>
|
||||
<authoring_tool>Blender 2.78.0</authoring_tool>
|
||||
</contributor>
|
||||
<created>2017-04-04T15:56:25</created>
|
||||
<modified>2017-04-04T15:56:25</modified>
|
||||
<unit name="meter" meter="1"/>
|
||||
<up_axis>Z_UP</up_axis>
|
||||
</asset>
|
||||
<library_images>
|
||||
<image id="checker_png" name="checker_png">
|
||||
<init_from>checker.png</init_from>
|
||||
</image>
|
||||
</library_images>
|
||||
<library_effects>
|
||||
<effect id="Material-effect">
|
||||
<profile_COMMON>
|
||||
<newparam sid="checker_png-surface">
|
||||
<surface type="2D">
|
||||
<init_from>checker_png</init_from>
|
||||
</surface>
|
||||
</newparam>
|
||||
<newparam sid="checker_png-sampler">
|
||||
<sampler2D>
|
||||
<source>checker_png-surface</source>
|
||||
</sampler2D>
|
||||
</newparam>
|
||||
<technique sid="common">
|
||||
<phong>
|
||||
<emission>
|
||||
<color sid="emission">1 1 1 1</color>
|
||||
</emission>
|
||||
<ambient>
|
||||
<color sid="ambient">1 1 1 1</color>
|
||||
</ambient>
|
||||
<diffuse>
|
||||
<texture texture="checker_png-sampler" texcoord="UVMap"/>
|
||||
</diffuse>
|
||||
<specular>
|
||||
<color sid="specular">0 0 0 1</color>
|
||||
</specular>
|
||||
<shininess>
|
||||
<float sid="shininess">50</float>
|
||||
</shininess>
|
||||
<index_of_refraction>
|
||||
<float sid="index_of_refraction">1</float>
|
||||
</index_of_refraction>
|
||||
</phong>
|
||||
</technique>
|
||||
</profile_COMMON>
|
||||
</effect>
|
||||
</library_effects>
|
||||
<library_materials>
|
||||
<material id="Material-material" name="Material">
|
||||
<instance_effect url="#Material-effect"/>
|
||||
</material>
|
||||
</library_materials>
|
||||
<library_geometries>
|
||||
<geometry id="Plane-mesh" name="Plane">
|
||||
<mesh>
|
||||
<source id="Plane-mesh-positions">
|
||||
<float_array id="Plane-mesh-positions-array" count="12">-1 -1 0 1 -1 0 -1 1 0 1 1 0</float_array>
|
||||
<technique_common>
|
||||
<accessor source="#Plane-mesh-positions-array" count="4" stride="3">
|
||||
<param name="X" type="float"/>
|
||||
<param name="Y" type="float"/>
|
||||
<param name="Z" type="float"/>
|
||||
</accessor>
|
||||
</technique_common>
|
||||
</source>
|
||||
<source id="Plane-mesh-normals">
|
||||
<float_array id="Plane-mesh-normals-array" count="3">0 0 1</float_array>
|
||||
<technique_common>
|
||||
<accessor source="#Plane-mesh-normals-array" count="1" stride="3">
|
||||
<param name="X" type="float"/>
|
||||
<param name="Y" type="float"/>
|
||||
<param name="Z" type="float"/>
|
||||
</accessor>
|
||||
</technique_common>
|
||||
</source>
|
||||
<source id="Plane-mesh-map-0">
|
||||
<float_array id="Plane-mesh-map-0-array" count="12">0.9999001 9.998e-5 9.998e-5 0.9999001 1.0004e-4 9.998e-5 0.9999001 9.998e-5 0.9999001 0.9999001 9.998e-5 0.9999001</float_array>
|
||||
<technique_common>
|
||||
<accessor source="#Plane-mesh-map-0-array" count="6" stride="2">
|
||||
<param name="S" type="float"/>
|
||||
<param name="T" type="float"/>
|
||||
</accessor>
|
||||
</technique_common>
|
||||
</source>
|
||||
<vertices id="Plane-mesh-vertices">
|
||||
<input semantic="POSITION" source="#Plane-mesh-positions"/>
|
||||
</vertices>
|
||||
<polylist material="Material-material" count="2">
|
||||
<input semantic="VERTEX" source="#Plane-mesh-vertices" offset="0"/>
|
||||
<input semantic="NORMAL" source="#Plane-mesh-normals" offset="1"/>
|
||||
<input semantic="TEXCOORD" source="#Plane-mesh-map-0" offset="2" set="0"/>
|
||||
<vcount>3 3 </vcount>
|
||||
<p>1 0 0 2 0 1 0 0 2 1 0 3 3 0 4 2 0 5</p>
|
||||
</polylist>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</library_geometries>
|
||||
<library_controllers/>
|
||||
<library_visual_scenes>
|
||||
<visual_scene id="Scene" name="Scene">
|
||||
<node id="Plane" name="Plane" type="NODE">
|
||||
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
|
||||
<instance_geometry url="#Plane-mesh" name="Plane">
|
||||
<bind_material>
|
||||
<technique_common>
|
||||
<instance_material symbol="Material-material" target="#Material-material">
|
||||
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
|
||||
</instance_material>
|
||||
</technique_common>
|
||||
</bind_material>
|
||||
</instance_geometry>
|
||||
</node>
|
||||
</visual_scene>
|
||||
</library_visual_scenes>
|
||||
<scene>
|
||||
<instance_visual_scene url="#Scene"/>
|
||||
</scene>
|
||||
</COLLADA>
|
16
checkerboard_plane/model.config
Normal file
16
checkerboard_plane/model.config
Normal file
@@ -0,0 +1,16 @@
|
||||
<?xml version="1.0"?>
|
||||
|
||||
<model>
|
||||
<name>Checkerboard Plane</name>
|
||||
<version>1.0</version>
|
||||
<sdf version='1.6'>checkerboard_plane.sdf</sdf>
|
||||
|
||||
<author>
|
||||
<name>Adam Allevato</name>
|
||||
<email>adam.d.allevato@gmail.com</email>
|
||||
</author>
|
||||
|
||||
<description>
|
||||
A plane with a reference checkerboard texture on it, used to validate and calibrate camera models. The checkerboard is 8x8 squares (like a standard checkerboard), and measures 2m on each side.
|
||||
</description>
|
||||
</model>
|
Reference in New Issue
Block a user