r200.sdf.jinja 2.86 KB
{%- set m = 0.050 -%}
{%- set l = 0.005 -%}
{%- set w = 0.030 -%}
{%- set h = 0.010 -%}
{%- set ixx = m/12*(w**2 + h**2) -%}
{%- set iyy = m/12*(l**2 + h**2) -%}
{%- set izz = m/12*(l**2 + w**2) -%}

{%- macro box(l, w, h) -%}
<geometry>
  <box>
    <size>{{l}} {{w}} {{h}}</size>
  </box>
</geometry>
{%- endmacro -%}

<?xml version="1.0" ?>
<sdf version="1.5">

  <model name="r200">

    <link name="link">

      <inertial>
        <mass>{{m}}</mass>
        <inertia>
          <ixx>{{ixx}}</ixx>
          <iyy>{{iyy}}</iyy>
          <izz>{{izz}}</izz>
        </inertia>
      </inertial>

      <visual name="visual">
        {{ box(l, w, h)|indent(8) }}
      </visual>

      <collision name="collision">
        {{ box(l, w, h)|indent(8) }}
      </collision>


      <sensor type="depth" name="r200_sensor">
        <always_on>true</always_on>
        <update_rate>3.0</update_rate>
        <visualize>true</visualize>
        <camera name="head">
          <horizontal_fov>1.3962634</horizontal_fov>
          <image>
            <width>640</width>
            <height>480</height>
            <format>R8G8B8</format>
          </image>
          <depth_camera>
            <output>1</output>
          </depth_camera>
          <clip>
            <near>0.02</near>
            <far>300</far>
          </clip>
          <noise>
            <type>gaussian</type>
            <!-- Noise is sampled independently per pixel on each frame.
                 That pixel's noise value is added to each of its color
                 channels, which at that point lie in the range [0,1]. -->
            <mean>0.0</mean>
            <stddev>0.007</stddev>
          </noise>
        </camera>

        <plugin name="r200_controller" filename="libgazebo_ros_openni_kinect.so">
          <baseline>0.2</baseline>
          <alwaysOn>true</alwaysOn>
          <updateRate>1.0</updateRate>
          <cameraName>r200_ir</cameraName>
          <imageTopicName>/r200/depth/image_raw</imageTopicName>
          <cameraInfoTopicName>/r200/depth/camera_info</cameraInfoTopicName>
          <depthImageTopicName>/r200/depth/image_raw</depthImageTopicName>
          <depthImageInfoTopicName>/r200/depth/camera_info</depthImageInfoTopicName>
          <pointCloudTopicName>/r200/depth/points</pointCloudTopicName>
          <frameName>r200</frameName>
          <pointCloudCutoff>0.5</pointCloudCutoff>
          <distortionK1>0.00000001</distortionK1>
          <distortionK2>0.00000001</distortionK2>
          <distortionK3>0.00000001</distortionK3>
          <distortionT1>0.00000001</distortionT1>
          <distortionT2>0.00000001</distortionT2>
          <CxPrime>0</CxPrime>
          <Cx>0</Cx>
          <Cy>0</Cy>
          <focalLength>0</focalLength>
          <hackBaseline>0</hackBaseline>
        </plugin>
      </sensor>
    </link>
  </model>

</sdf>


<!-- vim: set et ft=xml fenc=utf-8 ff=unix sts=0 sw=2 ts=2 : -->