model.sdf 4.83 KB
<?xml version="1.0"?>
<sdf version="1.6">
  <model name="realsense_camera">
    <plugin name="realsense_plugin" filename="libRealSensePlugin.so"/>
    <pose>0 0 0.015 0 0 0</pose>
    <link name="link">
      <inertial>
        <mass>0.0615752</mass>
        <inertia>
          <ixx>9.108e-05</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>2.51e-06</iyy>
          <iyz>0</iyz>
          <izz>8.931e-05</izz>
        </inertia>
        <pose>0 0 0 0 -0 0</pose>
      </inertial>
      <self_collide>0</self_collide>
      <kinematic>0</kinematic>
      <gravity>1</gravity>
      <visual name="visual">
        <geometry>
          <mesh>
            <uri>model://realsense_camera/meshes/realsense.dae</uri>
          </mesh>
        </geometry>
      </visual>
      <collision name='collision'>
        <laser_retro>0</laser_retro>
        <max_contacts>10</max_contacts>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <box>
            <size>0.0078 0.130 0.0192</size>
          </box>
        </geometry>
        <surface>
          <friction>
            <ode>
              <mu>1</mu>
              <mu2>1</mu2>
              <fdir1>0 0 0</fdir1>
              <slip1>0</slip1>
              <slip2>0</slip2>
            </ode>
          </friction>
          <bounce>
            <restitution_coefficient>0</restitution_coefficient>
            <threshold>1e+06</threshold>
          </bounce>
          <contact>
            <collide_without_contact>0</collide_without_contact>
            <collide_without_contact_bitmask>1</collide_without_contact_bitmask>
            <collide_bitmask>1</collide_bitmask>
            <ode>
              <soft_cfm>0</soft_cfm>
              <soft_erp>0.2</soft_erp>
              <kp>1e+13</kp>
              <kd>1</kd>
              <max_vel>0.01</max_vel>
              <min_depth>0</min_depth>
            </ode>
            <bullet>
              <split_impulse>1</split_impulse>
              <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
              <soft_cfm>0</soft_cfm>
              <soft_erp>0.2</soft_erp>
              <kp>1e+13</kp>
              <kd>1</kd>
            </bullet>
          </contact>
        </surface>
      </collision>
      <sensor name="color" type="camera">
        <pose>0 -0.046 0.004 0 0 0</pose>
        <camera name="__default__">
          <horizontal_fov>1.047</horizontal_fov>
          <image>
            <width>640</width>
            <height>480</height>
            <format>RGB_INT8</format>
          </image>
          <clip>
            <near>0.1</near>
            <far>100</far>
          </clip>
          <noise>
            <type>gaussian</type>
            <mean>0.0</mean>
            <stddev>0.007</stddev>
          </noise>
        </camera>
        <always_on>1</always_on>
        <update_rate>60</update_rate>
        <visualize>1</visualize>
      </sensor>
      <sensor name="ired1" type="camera">
        <pose>0 -0.06 0.004 0 0 0</pose>
        <camera name="__default__">
          <horizontal_fov>1.047</horizontal_fov>
          <image>
            <width>640</width>
            <height>480</height>
            <format>L_INT8</format>
          </image>
          <clip>
            <near>0.1</near>
            <far>100</far>
          </clip>
          <noise>
            <type>gaussian</type>
            <mean>0.0</mean>
            <stddev>0.007</stddev>
          </noise>
        </camera>
        <always_on>1</always_on>
        <update_rate>60</update_rate>
        <visualize>0</visualize>
      </sensor>
      <sensor name="ired2" type="camera">
        <pose>0 0.01 0.004 0 0 0</pose>
        <camera name="__default__">
          <horizontal_fov>1.047</horizontal_fov>
          <image>
            <width>640</width>
            <height>480</height>
            <format>L_INT8</format>
          </image>
          <clip>
            <near>0.1</near>
            <far>100</far>
          </clip>
          <noise>
            <type>gaussian</type>
            <mean>0.0</mean>
            <stddev>0.007</stddev>
          </noise>
        </camera>
        <always_on>1</always_on>
        <update_rate>60</update_rate>
        <visualize>0</visualize>
      </sensor>
      <sensor name="depth" type="depth">
        <pose>0 -0.03 0.004 0 0 0</pose>
        <camera name="__default__">
          <horizontal_fov>1.047</horizontal_fov>
          <image>
            <width>640</width>
            <height>480</height>
          </image>
          <clip>
            <near>0.1</near>
            <far>100</far>
          </clip>
          <noise>
            <type>gaussian</type>
            <mean>0.0</mean>
            <stddev>0.007</stddev>
          </noise>
        </camera>
        <always_on>1</always_on>
        <update_rate>60</update_rate>
        <visualize>0</visualize>
      </sensor>
    </link>
  </model>
</sdf>