mb1240-xl-ez4.sdf.jinja 1.42 KB
{# parameters #}
{%- set m = 0.005 -%}
{%- set l = 0.02 -%}
{%- set w = 0.02 -%}
{%- set h = 0.02 -%}
{%- set ixx = m/12*(w**2 + h**2) -%}
{%- set iyy = m/12*(l**2 + h**2) -%}
{%- set izz = m/12*(l**2 + w**2) -%}
{%- set deg2rad = 0.01745329251 -%}

{%- 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="mb1240-xl-ez4">

    <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) }}
        <material>
            <script>
              <uri>file://media/materials/scripts/gazebo.material</uri>
              <name>Gazebo/Grey</name>
            </script>
        </material>
      </visual>

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

      <sensor name="sonar" type="sonar">
        <pose>0 0 0 0 {{ 90*deg2rad }} 0</pose>
        <sonar>
          <min>0</min>
          <max>2.00</max>
          <radius>0.3</radius>
        </sonar>
        <always_on>1</always_on>
        <update_rate>30</update_rate>
        <visualize>true</visualize>
      </sensor>

    </link>

  </model>

</sdf>

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