Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <pcl/pcl_config.h>
00039 #ifdef HAVE_OPENNI
00040
00041 #ifndef __PCL_IO_OPENNI_GRABBER__
00042 #define __PCL_IO_OPENNI_GRABBER__
00043
00044 #include <Eigen/Core>
00045 #include <pcl/io/grabber.h>
00046 #include <pcl/io/openni_camera/openni_driver.h>
00047 #include <pcl/io/openni_camera/openni_device_kinect.h>
00048 #include <pcl/io/openni_camera/openni_image.h>
00049 #include <pcl/io/openni_camera/openni_depth_image.h>
00050 #include <pcl/io/openni_camera/openni_ir_image.h>
00051 #include <string>
00052 #include <deque>
00053 #include <boost/thread/mutex.hpp>
00054 #include <pcl/common/synchronizer.h>
00055
00056 namespace pcl
00057 {
00058 struct PointXYZ;
00059 struct PointXYZRGB;
00060 struct PointXYZRGBA;
00061 struct PointXYZI;
00062 template <typename T> class PointCloud;
00063
00068 class PCL_EXPORTS OpenNIGrabber : public Grabber
00069 {
00070 public:
00071
00072 typedef enum
00073 {
00074 OpenNI_Default_Mode = 0,
00075 OpenNI_SXGA_15Hz = 1,
00076 OpenNI_VGA_30Hz = 2,
00077 OpenNI_VGA_25Hz = 3,
00078 OpenNI_QVGA_25Hz = 4,
00079 OpenNI_QVGA_30Hz = 5,
00080 OpenNI_QVGA_60Hz = 6,
00081 OpenNI_QQVGA_25Hz = 7,
00082 OpenNI_QQVGA_30Hz = 8,
00083 OpenNI_QQVGA_60Hz = 9
00084 } Mode;
00085
00086
00087 typedef void (sig_cb_openni_image) (const boost::shared_ptr<openni_wrapper::Image>&);
00088 typedef void (sig_cb_openni_depth_image) (const boost::shared_ptr<openni_wrapper::DepthImage>&);
00089 typedef void (sig_cb_openni_ir_image) (const boost::shared_ptr<openni_wrapper::IRImage>&);
00090 typedef void (sig_cb_openni_image_depth_image) (const boost::shared_ptr<openni_wrapper::Image>&, const boost::shared_ptr<openni_wrapper::DepthImage>&, float constant) ;
00091 typedef void (sig_cb_openni_ir_depth_image) (const boost::shared_ptr<openni_wrapper::IRImage>&, const boost::shared_ptr<openni_wrapper::DepthImage>&, float constant) ;
00092 typedef void (sig_cb_openni_point_cloud) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZ> >&);
00093 typedef void (sig_cb_openni_point_cloud_rgb) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGB> >&);
00094 typedef void (sig_cb_openni_point_cloud_rgba) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGBA> >&);
00095 typedef void (sig_cb_openni_point_cloud_i) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZI> >&);
00096 typedef void (sig_cb_openni_point_cloud_eigen) (const boost::shared_ptr<const pcl::PointCloud<Eigen::MatrixXf> >&);
00097
00098 public:
00104 OpenNIGrabber (const std::string& device_id = "",
00105 const Mode& depth_mode = OpenNI_Default_Mode,
00106 const Mode& image_mode = OpenNI_Default_Mode);
00107
00109 virtual ~OpenNIGrabber () throw ();
00110
00112 virtual void
00113 start ();
00114
00116 virtual void
00117 stop ();
00118
00120 virtual bool
00121 isRunning () const;
00122
00123 virtual std::string
00124 getName () const;
00125
00127 virtual float
00128 getFramesPerSecond () const;
00129
00131 inline boost::shared_ptr<openni_wrapper::OpenNIDevice>
00132 getDevice () const;
00133
00135 std::vector<std::pair<int, XnMapOutputMode> >
00136 getAvailableDepthModes () const;
00137
00139 std::vector<std::pair<int, XnMapOutputMode> >
00140 getAvailableImageModes () const;
00141
00142 private:
00144 void
00145 onInit (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode);
00146
00148 void
00149 setupDevice (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode);
00150
00152 void
00153 updateModeMaps ();
00154
00156 void
00157 startSynchronization ();
00158
00160 void
00161 stopSynchronization ();
00162
00164 bool
00165 mapConfigMode2XnMode (int mode, XnMapOutputMode &xnmode) const;
00166
00167
00169 void
00170 imageCallback (boost::shared_ptr<openni_wrapper::Image> image, void* cookie);
00171
00173 void
00174 depthCallback (boost::shared_ptr<openni_wrapper::DepthImage> depth_image, void* cookie);
00175
00177 void
00178 irCallback (boost::shared_ptr<openni_wrapper::IRImage> ir_image, void* cookie);
00179
00181 void
00182 imageDepthImageCallback (const boost::shared_ptr<openni_wrapper::Image> &image,
00183 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image);
00184
00186 void
00187 irDepthImageCallback (const boost::shared_ptr<openni_wrapper::IRImage> &image,
00188 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image);
00189
00191 virtual void
00192 signalsChanged ();
00193
00194
00195
00197 virtual inline void
00198 checkImageAndDepthSynchronizationRequired ();
00199
00201 virtual inline void
00202 checkImageStreamRequired ();
00203
00205 virtual inline void
00206 checkDepthStreamRequired ();
00207
00209 virtual inline void
00210 checkIRStreamRequired ();
00211
00213 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ> >
00214 convertToXYZPointCloud (const boost::shared_ptr<openni_wrapper::DepthImage> &depth) const;
00215
00217 template <typename PointT> typename pcl::PointCloud<PointT>::Ptr
00218 convertToXYZRGBPointCloud (const boost::shared_ptr<openni_wrapper::Image> &image,
00219 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image) const;
00221 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> >
00222 convertToXYZIPointCloud (const boost::shared_ptr<openni_wrapper::IRImage> &image,
00223 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image) const;
00224
00225 Synchronizer<boost::shared_ptr<openni_wrapper::Image>, boost::shared_ptr<openni_wrapper::DepthImage> > rgb_sync_;
00226 Synchronizer<boost::shared_ptr<openni_wrapper::IRImage>, boost::shared_ptr<openni_wrapper::DepthImage> > ir_sync_;
00227
00233 boost::shared_ptr<pcl::PointCloud<Eigen::MatrixXf> >
00234 convertToEigenPointCloud (const boost::shared_ptr<openni_wrapper::Image> &image,
00235 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image) const;
00236
00238 boost::shared_ptr<openni_wrapper::OpenNIDevice> device_;
00239
00240 std::string rgb_frame_id_;
00241 std::string depth_frame_id_;
00242 unsigned image_width_;
00243 unsigned image_height_;
00244 unsigned depth_width_;
00245 unsigned depth_height_;
00246
00247 bool image_required_;
00248 bool depth_required_;
00249 bool ir_required_;
00250 bool sync_required_;
00251
00252 boost::signals2::signal<sig_cb_openni_image>* image_signal_;
00253 boost::signals2::signal<sig_cb_openni_depth_image>* depth_image_signal_;
00254 boost::signals2::signal<sig_cb_openni_ir_image>* ir_image_signal_;
00255 boost::signals2::signal<sig_cb_openni_image_depth_image>* image_depth_image_signal_;
00256 boost::signals2::signal<sig_cb_openni_ir_depth_image>* ir_depth_image_signal_;
00257 boost::signals2::signal<sig_cb_openni_point_cloud>* point_cloud_signal_;
00258 boost::signals2::signal<sig_cb_openni_point_cloud_i>* point_cloud_i_signal_;
00259 boost::signals2::signal<sig_cb_openni_point_cloud_rgb>* point_cloud_rgb_signal_;
00260 boost::signals2::signal<sig_cb_openni_point_cloud_rgba>* point_cloud_rgba_signal_;
00261 boost::signals2::signal<sig_cb_openni_point_cloud_eigen>* point_cloud_eigen_signal_;
00262
00263 struct modeComp
00264 {
00265
00266 bool operator () (const XnMapOutputMode& mode1, const XnMapOutputMode & mode2) const
00267 {
00268 if (mode1.nXRes < mode2.nXRes)
00269 return true;
00270 else if (mode1.nXRes > mode2.nXRes)
00271 return false;
00272 else if (mode1.nYRes < mode2.nYRes)
00273 return true;
00274 else if (mode1.nYRes > mode2.nYRes)
00275 return false;
00276 else if (mode1.nFPS < mode2.nFPS)
00277 return true;
00278 else
00279 return false;
00280 }
00281 } ;
00282 std::map<int, XnMapOutputMode> config2xn_map_;
00283
00284 openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle;
00285 openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle;
00286 openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle;
00287 bool running_;
00288
00289 public:
00290 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00291 };
00292
00293 boost::shared_ptr<openni_wrapper::OpenNIDevice>
00294 OpenNIGrabber::getDevice () const
00295 {
00296 return device_;
00297 }
00298
00299 }
00300 #endif // __PCL_IO_OPENNI_GRABBER__
00301 #endif // HAVE_OPENNI