In this tutorial, you'll learn how to connect a Gazebo depth camera to ROS. The tutorial consists of 3 main steps:
This is a self-contained tutorial; it does not use the RRBot that is developed in other Gazebo ROS tutorials. It is designed to help you get up and running quickly using computer vision in ROS and Gazebo.
You should install gazebo_ros_pkgs before doing this tutorial.
Because Gazebo and ROS are separate projects that do not depend on each other,
sensors from the gazebo_models
repository (such as depth cameras) do not
include ROS plugins by default. This means you have to make a custom camera
based on those in the Gazebo model repository, and then add your own <plugin>
tag to make the depth camera data publish point clouds and images to ROS topics.
You should choose a depth camera to use from those available in Gazebo. This tutorial will use the Microsoft Kinect, but the procedure should be the same for other depth cameras on the list.
First, acquire the depth camera and modify its name. We've packaged the Kinect
sensor from gazebo_models
repository for you, so all you have to do is
download
and unzip it.
Alternatively, you can follow the
model contribution tutorial
to make your own camera from scratch, or you can clone the gazebo_models
repository and copy one of the sensors from there.
However you acquire it, copy the kinect
folder into your
~/.gazebo/models
directory. Then, change the name of your model to something
meaningful, like kinect_ros
. To change the model's name, you should update
the folder name, the <name>
stored in the .config
file, and the model name
in the model.sdf
file.
Now you need to add the ROS plugin to publish depth camera information and output to ROS topics. A list of ROS plugins, with example code, can be found in the plugins tutorial.
In this tutorial, you'll be using the generic "Openni Kinect" plugin. You can (and should) use this plugin for other types of depth cameras besides the Kinect (it's an older plugin, and so it retains its old name).
Open the model.sdf
file in your new model's directory. Add the following SDF
markup inside the <sensor>
tag, immediately after the closing </camera>
tag:
<plugin name="camera_plugin" filename="libgazebo_ros_openni_kinect.so">
<baseline>0.2</baseline>
<alwaysOn>true</alwaysOn>
<!-- Keep this zero, update_rate in the parent <sensor> tag
will control the frame rate. -->
<updateRate>0.0</updateRate>
<cameraName>camera_ir</cameraName>
<imageTopicName>/camera/color/image_raw</imageTopicName>
<cameraInfoTopicName>/camera/color/camera_info</cameraInfoTopicName>
<depthImageTopicName>/camera/depth/image_raw</depthImageTopicName>
<depthImageCameraInfoTopicName>/camera/depth/camera_info</depthImageCameraInfoTopicName>
<pointCloudTopicName>/camera/depth/points</pointCloudTopicName>
<frameName>camera_link</frameName>
<pointCloudCutoff>0.5</pointCloudCutoff>
<pointCloudCutoffMax>3.0</pointCloudCutoffMax>
<distortionK1>0</distortionK1>
<distortionK2>0</distortionK2>
<distortionK3>0</distortionK3>
<distortionT1>0</distortionT1>
<distortionT2>0</distortionT2>
<CxPrime>0</CxPrime>
<Cx>0</Cx>
<Cy>0</Cy>
<focalLength>0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
As you can see, this plugin allows you a lot of fine-grained control over how the information is passed to ROS. A few points to note:
updateRate
parameter should be set to 0, which will cause the plugin
to publish depth information as the same rate as the parent SDF sensor
. If
updateRate is not 0, it will do additional throttling on top of the parent
sensor
's update rate.frameName
can be set to whatever you'd like, but the
ones shown above match the default topics that are published by commonly used
ROS packages, such as openni2_launch
. Keeping the topic names the same will
help make switching between real and simulated cameras easier.distortionX
parameters should match those in the <distortion>
tag of
the parent camera. If there is no <distortion>
tag, then use 0 for all the
distortionX
values.pointCloudCutoff
and pointCloudCutoffMax
is the minimum and maximum distance for points, respectively. No points beyond
this distance will be shown. This is an additional restriction to any
clipping that has been set in the parent sensor.Once you've renamed the model, added the above code to your .sdf
file, and
saved your changes, you should be ready to roll!
Open Gazebo with ROS support enabled (e.g.
roslaunch gazebo_ros empty_world.launch
). Use the Insert panel to find your
"Kinect ROS" model, and insert it into the world.
Important: You should also add some other objects to the scene, otherwise your camera might not have anything to see! Add some cubes, spheres, or anything else, and make sure they are located in the visible range of the camera, like in the screenshot below.
/rosdepthcamera/rviz_topics.png' width='600px'/>
After setting the correct topics and fixed frame, you should see something similar to the following from the PointCloud2: