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
00039 #include <pcl/pcl_config.h>
00040 #ifdef HAVE_OPENNI
00041
00042 #ifndef __PCL_IO_OPENNI_GRABBER__
00043 #define __PCL_IO_OPENNI_GRABBER__
00044
00045 #include <pcl/io/eigen.h>
00046 #include <pcl/io/boost.h>
00047 #include <pcl/io/grabber.h>
00048 #include <pcl/io/openni_camera/openni_driver.h>
00049 #include <pcl/io/openni_camera/openni_device_kinect.h>
00050 #include <pcl/io/openni_camera/openni_image.h>
00051 #include <pcl/io/openni_camera/openni_depth_image.h>
00052 #include <pcl/io/openni_camera/openni_ir_image.h>
00053 #include <string>
00054 #include <deque>
00055 #include <pcl/common/synchronizer.h>
00056
00057 namespace pcl
00058 {
00059 struct PointXYZ;
00060 struct PointXYZRGB;
00061 struct PointXYZRGBA;
00062 struct PointXYZI;
00063 template <typename T> class PointCloud;
00064
00069 class PCL_EXPORTS OpenNIGrabber : public Grabber
00070 {
00071 public:
00072 typedef boost::shared_ptr<OpenNIGrabber> Ptr;
00073 typedef boost::shared_ptr<const OpenNIGrabber> ConstPtr;
00074
00075 typedef enum
00076 {
00077 OpenNI_Default_Mode = 0,
00078 OpenNI_SXGA_15Hz = 1,
00079 OpenNI_VGA_30Hz = 2,
00080 OpenNI_VGA_25Hz = 3,
00081 OpenNI_QVGA_25Hz = 4,
00082 OpenNI_QVGA_30Hz = 5,
00083 OpenNI_QVGA_60Hz = 6,
00084 OpenNI_QQVGA_25Hz = 7,
00085 OpenNI_QQVGA_30Hz = 8,
00086 OpenNI_QQVGA_60Hz = 9
00087 } Mode;
00088
00089
00090 typedef void (sig_cb_openni_image) (const boost::shared_ptr<openni_wrapper::Image>&);
00091 typedef void (sig_cb_openni_depth_image) (const boost::shared_ptr<openni_wrapper::DepthImage>&);
00092 typedef void (sig_cb_openni_ir_image) (const boost::shared_ptr<openni_wrapper::IRImage>&);
00093 typedef void (sig_cb_openni_image_depth_image) (const boost::shared_ptr<openni_wrapper::Image>&, const boost::shared_ptr<openni_wrapper::DepthImage>&, float constant) ;
00094 typedef void (sig_cb_openni_ir_depth_image) (const boost::shared_ptr<openni_wrapper::IRImage>&, const boost::shared_ptr<openni_wrapper::DepthImage>&, float constant) ;
00095 typedef void (sig_cb_openni_point_cloud) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZ> >&);
00096 typedef void (sig_cb_openni_point_cloud_rgb) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGB> >&);
00097 typedef void (sig_cb_openni_point_cloud_rgba) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGBA> >&);
00098 typedef void (sig_cb_openni_point_cloud_i) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZI> >&);
00099
00100 public:
00106 OpenNIGrabber (const std::string& device_id = "",
00107 const Mode& depth_mode = OpenNI_Default_Mode,
00108 const Mode& image_mode = OpenNI_Default_Mode);
00109
00111 virtual ~OpenNIGrabber () throw ();
00112
00114 virtual void
00115 start ();
00116
00118 virtual void
00119 stop ();
00120
00122 virtual bool
00123 isRunning () const;
00124
00125 virtual std::string
00126 getName () const;
00127
00129 virtual float
00130 getFramesPerSecond () const;
00131
00133 inline boost::shared_ptr<openni_wrapper::OpenNIDevice>
00134 getDevice () const;
00135
00137 std::vector<std::pair<int, XnMapOutputMode> >
00138 getAvailableDepthModes () const;
00139
00141 std::vector<std::pair<int, XnMapOutputMode> >
00142 getAvailableImageModes () const;
00143
00152 inline void
00153 setRGBCameraIntrinsics (const double rgb_focal_length_x,
00154 const double rgb_focal_length_y,
00155 const double rgb_principal_point_x,
00156 const double rgb_principal_point_y)
00157 {
00158 rgb_focal_length_x_ = rgb_focal_length_x;
00159 rgb_focal_length_y_ = rgb_focal_length_y;
00160 rgb_principal_point_x_ = rgb_principal_point_x;
00161 rgb_principal_point_y_ = rgb_principal_point_y;
00162 }
00163
00170 inline void
00171 getRGBCameraIntrinsics (double &rgb_focal_length_x,
00172 double &rgb_focal_length_y,
00173 double &rgb_principal_point_x,
00174 double &rgb_principal_point_y) const
00175 {
00176 rgb_focal_length_x = rgb_focal_length_x_;
00177 rgb_focal_length_y = rgb_focal_length_y_;
00178 rgb_principal_point_x = rgb_principal_point_x_;
00179 rgb_principal_point_y = rgb_principal_point_y_;
00180 }
00181
00182
00189 inline void
00190 setRGBFocalLength (const double rgb_focal_length)
00191 {
00192 rgb_focal_length_x_ = rgb_focal_length_y_ = rgb_focal_length;
00193 }
00194
00202 inline void
00203 setRGBFocalLength (const double rgb_focal_length_x, const double rgb_focal_length_y)
00204 {
00205 rgb_focal_length_x_ = rgb_focal_length_x;
00206 rgb_focal_length_y_ = rgb_focal_length_y;
00207 }
00208
00213 inline void
00214 getRGBFocalLength (double &rgb_focal_length_x, double &rgb_focal_length_y) const
00215 {
00216 rgb_focal_length_x = rgb_focal_length_x_;
00217 rgb_focal_length_y = rgb_focal_length_y_;
00218 }
00219
00228 inline void
00229 setDepthCameraIntrinsics (const double depth_focal_length_x,
00230 const double depth_focal_length_y,
00231 const double depth_principal_point_x,
00232 const double depth_principal_point_y)
00233 {
00234 depth_focal_length_x_ = depth_focal_length_x;
00235 depth_focal_length_y_ = depth_focal_length_y;
00236 depth_principal_point_x_ = depth_principal_point_x;
00237 depth_principal_point_y_ = depth_principal_point_y;
00238 }
00239
00246 inline void
00247 getDepthCameraIntrinsics (double &depth_focal_length_x,
00248 double &depth_focal_length_y,
00249 double &depth_principal_point_x,
00250 double &depth_principal_point_y) const
00251 {
00252 depth_focal_length_x = depth_focal_length_x_;
00253 depth_focal_length_y = depth_focal_length_y_;
00254 depth_principal_point_x = depth_principal_point_x_;
00255 depth_principal_point_y = depth_principal_point_y_;
00256 }
00257
00263 inline void
00264 setDepthFocalLength (const double depth_focal_length)
00265 {
00266 depth_focal_length_x_ = depth_focal_length_y_ = depth_focal_length;
00267 }
00268
00269
00276 inline void
00277 setDepthFocalLength (const double depth_focal_length_x, const double depth_focal_length_y)
00278 {
00279 depth_focal_length_x_ = depth_focal_length_x;
00280 depth_focal_length_y_ = depth_focal_length_y;
00281 }
00282
00287 inline void
00288 getDepthFocalLength (double &depth_focal_length_x, double &depth_focal_length_y) const
00289 {
00290 depth_focal_length_x = depth_focal_length_x_;
00291 depth_focal_length_y = depth_focal_length_y_;
00292 }
00293
00299 inline void
00300 convertShiftToDepth (
00301 const uint16_t* shift_data_ptr,
00302 uint16_t* depth_data_ptr,
00303 std::size_t size) const
00304 {
00305
00306 boost::shared_ptr<openni_wrapper::OpenNIDevice> openni_device =
00307 this->getDevice ();
00308
00309 const uint16_t* shift_data_it = shift_data_ptr;
00310 uint16_t* depth_data_it = depth_data_ptr;
00311
00312
00313 for (std::size_t i=0; i<size; ++i)
00314 {
00315 *depth_data_it = openni_device->shiftToDepth(*shift_data_it);
00316
00317 shift_data_it++;
00318 depth_data_it++;
00319 }
00320
00321 }
00322
00323
00324 protected:
00326 void
00327 onInit (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode);
00328
00330 void
00331 setupDevice (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode);
00332
00334 void
00335 updateModeMaps ();
00336
00338 void
00339 startSynchronization ();
00340
00342 void
00343 stopSynchronization ();
00344
00346 bool
00347 mapConfigMode2XnMode (int mode, XnMapOutputMode &xnmode) const;
00348
00349
00351 virtual void
00352 imageCallback (boost::shared_ptr<openni_wrapper::Image> image, void* cookie);
00353
00355 virtual void
00356 depthCallback (boost::shared_ptr<openni_wrapper::DepthImage> depth_image, void* cookie);
00357
00359 virtual void
00360 irCallback (boost::shared_ptr<openni_wrapper::IRImage> ir_image, void* cookie);
00361
00363 virtual void
00364 imageDepthImageCallback (const boost::shared_ptr<openni_wrapper::Image> &image,
00365 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image);
00366
00368 virtual void
00369 irDepthImageCallback (const boost::shared_ptr<openni_wrapper::IRImage> &image,
00370 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image);
00371
00373 virtual void
00374 signalsChanged ();
00375
00376
00377
00379 virtual void
00380 checkImageAndDepthSynchronizationRequired ();
00381
00383 virtual void
00384 checkImageStreamRequired ();
00385
00387 virtual void
00388 checkDepthStreamRequired ();
00389
00391 virtual void
00392 checkIRStreamRequired ();
00393
00394
00398 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ> >
00399 convertToXYZPointCloud (const boost::shared_ptr<openni_wrapper::DepthImage> &depth) const;
00400
00405 template <typename PointT> typename pcl::PointCloud<PointT>::Ptr
00406 convertToXYZRGBPointCloud (const boost::shared_ptr<openni_wrapper::Image> &image,
00407 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image) const;
00408
00413 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> >
00414 convertToXYZIPointCloud (const boost::shared_ptr<openni_wrapper::IRImage> &image,
00415 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image) const;
00416
00417
00418 Synchronizer<boost::shared_ptr<openni_wrapper::Image>, boost::shared_ptr<openni_wrapper::DepthImage> > rgb_sync_;
00419 Synchronizer<boost::shared_ptr<openni_wrapper::IRImage>, boost::shared_ptr<openni_wrapper::DepthImage> > ir_sync_;
00420
00422 boost::shared_ptr<openni_wrapper::OpenNIDevice> device_;
00423
00424 std::string rgb_frame_id_;
00425 std::string depth_frame_id_;
00426 unsigned image_width_;
00427 unsigned image_height_;
00428 unsigned depth_width_;
00429 unsigned depth_height_;
00430
00431 bool image_required_;
00432 bool depth_required_;
00433 bool ir_required_;
00434 bool sync_required_;
00435
00436 boost::signals2::signal<sig_cb_openni_image>* image_signal_;
00437 boost::signals2::signal<sig_cb_openni_depth_image>* depth_image_signal_;
00438 boost::signals2::signal<sig_cb_openni_ir_image>* ir_image_signal_;
00439 boost::signals2::signal<sig_cb_openni_image_depth_image>* image_depth_image_signal_;
00440 boost::signals2::signal<sig_cb_openni_ir_depth_image>* ir_depth_image_signal_;
00441 boost::signals2::signal<sig_cb_openni_point_cloud>* point_cloud_signal_;
00442 boost::signals2::signal<sig_cb_openni_point_cloud_i>* point_cloud_i_signal_;
00443 boost::signals2::signal<sig_cb_openni_point_cloud_rgb>* point_cloud_rgb_signal_;
00444 boost::signals2::signal<sig_cb_openni_point_cloud_rgba>* point_cloud_rgba_signal_;
00445
00446 struct modeComp
00447 {
00448
00449 bool operator () (const XnMapOutputMode& mode1, const XnMapOutputMode & mode2) const
00450 {
00451 if (mode1.nXRes < mode2.nXRes)
00452 return true;
00453 else if (mode1.nXRes > mode2.nXRes)
00454 return false;
00455 else if (mode1.nYRes < mode2.nYRes)
00456 return true;
00457 else if (mode1.nYRes > mode2.nYRes)
00458 return false;
00459 else if (mode1.nFPS < mode2.nFPS)
00460 return true;
00461 else
00462 return false;
00463 }
00464 } ;
00465 std::map<int, XnMapOutputMode> config2xn_map_;
00466
00467 openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle;
00468 openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle;
00469 openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle;
00470 bool running_;
00471
00473 double rgb_focal_length_x_;
00475 double rgb_focal_length_y_;
00477 double rgb_principal_point_x_;
00479 double rgb_principal_point_y_;
00481 double depth_focal_length_x_;
00483 double depth_focal_length_y_;
00485 double depth_principal_point_x_;
00487 double depth_principal_point_y_;
00488
00489 public:
00490 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00491 };
00492
00493 boost::shared_ptr<openni_wrapper::OpenNIDevice>
00494 OpenNIGrabber::getDevice () const
00495 {
00496 return device_;
00497 }
00498
00499 }
00500 #endif // __PCL_IO_OPENNI_GRABBER__
00501 #endif // HAVE_OPENNI