Gazebo | Ignition | Community
Ask Your Question
0

intel realsense sr300 in simulation

asked 2018-04-19 20:08:33 -0500

lr101095 gravatar image

gazebo 7, ros kinetic, ubuntu 16.04

is a simulation for the intel realsense sr300 available in gazebo 7? i understand that the kinect would be a good substitute in simulation, but i have access to a the real sr300 camera and i was planning on making comparisons between simulation and the real output from the camera.

if anyone has any suggestions, it would be greatly appreciated.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-04-23 11:08:05 -0500

shreeyak gravatar image

updated 2018-04-23 11:26:21 -0500

Yes, a google search does reveal that there are some models available for simulation of the realsense camera. See these links:
https://github.com/intel/gazebo-reals...
https://github.com/SyrianSpock/realse...

To know more about plugins in Gazebo, take a look at the official Tutorial: Using Gazebo plugins with ROS.

That said, for most applications, you can probably use the generic DepthCam or Kinect plugin. I've been using the Asus Xtion Pro simulation of the camera, based on the libgazebo_ros_openni_kinect.so plugin, for emulating a realsense camera and it's working well. I based it on a project from the book Effective Robotics Programming with ROS.

To make this plugin emulate your camera, modify the elements in the <sensors> tag withing the <gazebo> tag to provide parameters like your horizontal FOV, minimum depth, maximum depth, etc. I've left those parameters default in my simulation but have modified the topic names to be the same as my actual camera. See my files below.

Here is the xtion_pro_live.gazebo.xacro file. Note that I replaced the mesh files with a realsense mesh, from the links above. <robot xmlns:xacro="http://ros.org/wiki/xacro"> <xacro:include filename="$(find robot_description)/urdf/deg_to_rad.xacro"/>

  <xacro:macro name="xtion_pro_live_rgbd_camera_gazebo" params="name">
    <gazebo reference="${name}_link">

      <static>true</static>
      <turnGravityOff>true</turnGravityOff>

      <!-- RGB + Depth -->
      <sensor type="depth" name="${name}_frame_sensor2">
        <always_on>true</always_on>
        <update_rate>6.0</update_rate>

        <camera>
          <horizontal_fov>${58.0 * deg_to_rad}</horizontal_fov>
          <image>
            <format>R8G8B8</format>
            <width>640</width>
            <height>480</height>
          </image>
          <clip>
            <near>0.05</near>
            <far>4.0</far>
          </clip>
          <noise>
            <type>gaussian</type>
            <mean>0.0</mean>
            <stddev>0.005</stddev>
          </noise>
        </camera>

        <plugin name="${name}_frame_controller" filename="libgazebo_ros_openni_kinect.so">
          <alwaysOn>true</alwaysOn>
          <updateRate>6.0</updateRate>
          <cameraName>${name}</cameraName>
          <imageTopicName>color/image_raw</imageTopicName>
          <depthImageTopicName>depth/image_rect_raw</depthImageTopicName>
          <cameraInfoTopicName>color/camera_info</cameraInfoTopicName>
          <depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
          <pointCloudTopicName>depth_registered/points</pointCloudTopicName>
          <frameName>${name}_color_optical_frame</frameName>
          <pointCloudCutoff>0.05</pointCloudCutoff>
          <rangeMax>4.0</rangeMax>
        </plugin>
      </sensor>
    </gazebo>
  </xacro:macro>
</robot>

Here is the xtion_pro_live.urdf.xacro file:

<?xmlversion="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">

  <xacro:include filename="$(find robot_description)/urdf/sensors/xtion_pro_live.gazebo.xacro"/>
  <xacro:include filename="$(find robot_description)/urdf/deg_to_rad.xacro"/>

  <xacro:macro name="dummy_inertial">
    <inertial>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <mass value="0.001"/>
      <inertia ixx="0.00001" ixy="0" ixz="0"
               iyy="0.00001" iyz="0"
               izz="0.00001"/>
    </inertial>
  </xacro:macro>

  <xacro:macro name="xtion_pro_live" params="name parent_link *origin *optical_origin">

    <!-- frames in the center of the camera -->
    <joint name="${name}_joint" type="fixed">
      <xacro:insert_block name="origin"/>
      <parent link="${parent_link}"/>
      <child link="${name}_link"/>
    </joint>

    <link name="${name}_link">
      <inertial>
        <origin xyz="-0.00936000000 -0.00003000000 -0.00273000000" rpy="0 0 0"/>
        <mass value="0.21970000000"/>
        <inertia ixx="0.00000429247" ixy="0.00000000000" ixz="0.00000002565"
                 iyy="0.00000008027" iyz="0.00000000000"
                 izz="0.00000427339"/>
      </inertial>
      <visual>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
          <mesh filename="package://robot_description/meshes/realsense/intel_d415.dae"/>
        </geometry>
        <material name="DarkGrey ...
(more)
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-04-19 20:08:33 -0500

Seen: 2,541 times

Last updated: Apr 23 '18