1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210
|
.. _openni_grabber:
The OpenNI Grabber Framework in PCL
-----------------------------------
As of PCL 1.0, we offer a new generic grabber interface to provide a smooth and
convenient access to different devices and their drivers, file formats and
other sources of data.
The first driver that we incorporated is the new OpenNI Grabber, which makes it
a breeze to request data streams from OpenNI compatible cameras. This tutorial
presents how to set up and use the grabber, and since it's so simple, we can
keep it short :).
The cameras that we have tested so far are the `Primesense Reference Design <http://www.primesense.com/>`_, `Microsoft Kinect <http://www.xbox.com/kinect/>`_ and `Asus Xtion Pro <http://event.asus.com/wavi/product/WAVI_Pro.aspx>`_ cameras:
.. image:: images/openni_cams.jpg
:height: 390px
Simple Example
--------------
In *visualization*, there is a very short piece of code which contains all that
is required to set up a *pcl::PointCloud<XYZ>* or *pcl::PointCloud<XYZRGB>*
cloud callback.
Here is a screenshot and a video of the PCL OpenNI Viewer in action, which uses
the OpenNI Grabber.
.. image:: images/pcl_openni_viewer.jpg
:height: 390px
:target: _images/pcl_openni_viewer.jpg
.. raw:: html
<iframe title="PCL OpenNI Viewer example" width="480" height="390" src="http://www.youtube.com/embed/x3SaWQkPsPI?rel=0" frameborder="0" allowfullscreen></iframe>
So let's look at the code. From *visualization/tools/openni_viewer_simple.cpp*
.. code-block:: cpp
:linenos:
#include <pcl/io/openni_grabber.h>
#include <pcl/visualization/cloud_viewer.h>
class SimpleOpenNIViewer
{
public:
SimpleOpenNIViewer () : viewer ("PCL OpenNI Viewer") {}
void cloud_cb_ (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud)
{
if (!viewer.wasStopped())
viewer.showCloud (cloud);
}
void run ()
{
pcl::Grabber* interface = new pcl::OpenNIGrabber();
boost::function<void (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr&)> f =
boost::bind (&SimpleOpenNIViewer::cloud_cb_, this, _1);
interface->registerCallback (f);
interface->start ();
while (!viewer.wasStopped())
{
boost::this_thread::sleep (boost::posix_time::seconds (1));
}
interface->stop ();
}
pcl::visualization::CloudViewer viewer;
};
int main ()
{
SimpleOpenNIViewer v;
v.run ();
return 0;
}
As you can see, the *run ()* function of *SimpleOpenNIViewer* first creates a
new *OpenNIGrabber* interface. The next line might seem a bit intimidating at
first, but it's not that bad. We create a *boost::bind* object with the address
of the callback *cloud_cb_*, we pass a reference to our *SimpleOpenNIViewer*
and the argument place holder *_1*.
The *bind* then gets casted to a *boost::function* object which is templated on
the callback function type, in this case *void (const
pcl::PointCloud<pcl::PointXYZ>::ConstPtr&)*. The resulting function object can
the be registered with the *OpenNIGrabber* and subsequently started. Note that
the *stop ()* method does not necessarily need to be called, as the destructor
takes care of that.
Additional Details
------------------
The *OpenNIGrabber* offers more than one datatype, which is the reason we made
the *Grabber* interface so generic, leading to the relatively complicated
*boost::bind* line. In fact, we can register the following callback types as of
this writing:
* `void (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGB> >&)`
* `void (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZ> >&)`
* `void (const boost::shared_ptr<openni_wrapper::Image>&)`
This provides just the RGB image from the built-in camera.
* `void (const boost::shared_ptr<openni_wrapper::DepthImage>&)`
This provides the depth image, without any color or intensity information
* `void (const boost::shared_ptr<openni_wrapper::Image>&, const boost::shared_ptr<openni_wrapper::DepthImage>&, float constant)`
When a callback of this type is registered, the grabber sends both RGB
image and depth image and the constant (*1 / focal length*), which you need
if you want to do your own disparity conversion.
.. note::
All callback types that need a depth _and_ image stream have a
synchronization mechanism enabled which ensures consistent depth and image
data. This introduces a small lag, since the synchronizer needs to wait at
least for one more set of images before sending the first ones.
Starting and stopping streams
-----------------------------
The *registerCallback* call returns a *boost::signals2::connection* object,
which we ignore in the above example. However, if you want to interrupt or
cancel one or more of the registered data streams, you can call disconnect the
callback without stopping the whole grabber:
.. code-block:: cpp
boost::signals2::connection = interface (registerCallback (f));
// ...
if (c.connected ())
c.disconnect ();
Benchmark
---------
The following code snippet will attempt to subscribe to both the *depth* and
*color* streams, and is provided as a way to benchmark your system. If your
computer is too slow, and you might not be able to get ~29Hz+, please contact
us. We might be able to optimize the code even further.
.. literalinclude:: sources/openni_grabber/openni_grabber.cpp
:language: cpp
:linenos:
Compiling and running the program
---------------------------------
Add the following lines to your CMakeLists.txt file:
.. literalinclude:: sources/openni_grabber/CMakeLists.txt
:language: cmake
:linenos:
Troubleshooting
---------------
Q: I get an error that there's no device connected:
.. note::
[OpenNIGrabber] No devices connected.
terminate called after throwing an instance of 'pcl::PCLIOException'
what(): pcl::OpenNIGrabber::OpenNIGrabber(const std::string&) in openni_grabber.cpp @ 69: Device could not be initialized or no devices found.
[1] 8709 abort openni_viewer
A: most probably this is a problem with the XnSensorServer. Do you have the
ps-engine package installed? Is there a old process of XnSensorServer hanging
around, try kill it.
Q: I get an error about a closed network connection:
.. note::
terminate called after throwing an instance of 'pcl::PCLIOException'
what(): No matching device found. openni_wrapper::OpenNIDevice::OpenNIDevice(xn::Context&, const xn::NodeInfo&, const xn::NodeInfo&, const xn::NodeInfo&, const xn::NodeInfo&) @ /home/andreas/pcl/pcl/trunk/io/src/openni_camera/openni_device.cpp @ 96 : creating depth generator failed. Reason: The network connection has been closed!
A: This error can occur with newer Linux kernels that include the *gspca_kinect* kernel module. The module claims the usb interface of the kinect and prevents OpenNI from doing so.
You can either remove the kernel module (*rmmod gspca_kinect*) or blacklist it (by executing *echo "blacklist gspca_kinect" > /etc/modprobe.d/blacklist-psengine.conf* as root).
The OpenNI Ubuntu packages provided by PCL already include this fix, but you might need it in other distributions.
Conclusion
----------
The Grabber interface is very powerful and general and makes it a breeze to
connect to OpenNI compatible cameras in your code. We are in the process of
writing a FileGrabber which can be used using the same interface, and can e.g.
load all Point Cloud files from a directory and provide them to the callback at
a certain rate. The only change required is
the allocation of the Grabber Object (*pcl::Grabber *g = new ...;*).
If you have a sensor which you would like to have available within PCL, just
let us know at *pcl-developers@pointclouds.org*, and we will figure something
out.
|