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 #include <pcl/pcl_config.h>
00038 #ifdef HAVE_OPENNI
00039
00040 #ifndef __PCL_IO_ONI_PLAYER__
00041 #define __PCL_IO_ONI_PLAYER__
00042
00043 #include <Eigen/Core>
00044 #include <pcl/io/grabber.h>
00045 #include <pcl/io/openni_camera/openni_driver.h>
00046 #include <pcl/io/openni_camera/openni_device_oni.h>
00047 #include <pcl/io/openni_camera/openni_image.h>
00048 #include <pcl/io/openni_camera/openni_depth_image.h>
00049 #include <pcl/io/openni_camera/openni_ir_image.h>
00050 #include <string>
00051 #include <deque>
00052 #include <boost/thread/mutex.hpp>
00053 #include <pcl/common/synchronizer.h>
00054
00055
00056 namespace pcl
00057 {
00058 struct PointXYZ;
00059 struct PointXYZRGB;
00060 struct PointXYZRGBA;
00061 struct PointXYZI;
00062 template <typename T> class PointCloud;
00063
00067 class PCL_EXPORTS ONIGrabber : public Grabber
00068 {
00069 public:
00070
00071 typedef void (sig_cb_openni_image) (const boost::shared_ptr<openni_wrapper::Image>&);
00072 typedef void (sig_cb_openni_depth_image) (const boost::shared_ptr<openni_wrapper::DepthImage>&);
00073 typedef void (sig_cb_openni_ir_image) (const boost::shared_ptr<openni_wrapper::IRImage>&);
00074 typedef void (sig_cb_openni_image_depth_image) (const boost::shared_ptr<openni_wrapper::Image>&, const boost::shared_ptr<openni_wrapper::DepthImage>&, float constant) ;
00075 typedef void (sig_cb_openni_ir_depth_image) (const boost::shared_ptr<openni_wrapper::IRImage>&, const boost::shared_ptr<openni_wrapper::DepthImage>&, float constant) ;
00076 typedef void (sig_cb_openni_point_cloud) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZ> >&);
00077 typedef void (sig_cb_openni_point_cloud_rgb) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGB> >&);
00078 typedef void (sig_cb_openni_point_cloud_rgba) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGBA> >&);
00079 typedef void (sig_cb_openni_point_cloud_i) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZI> >&);
00080
00086 ONIGrabber (const std::string& file_name, bool repeat, bool stream);
00087
00089 virtual ~ONIGrabber () throw ();
00090
00094 virtual void
00095 start ();
00096
00100 virtual void
00101 stop ();
00102
00106 virtual std::string
00107 getName () const;
00108
00112 virtual bool
00113 isRunning () const;
00114
00116 virtual float
00117 getFramesPerSecond () const;
00118
00119 protected:
00121 void
00122 imageCallback (boost::shared_ptr<openni_wrapper::Image> image, void* cookie);
00123
00125 void
00126 depthCallback (boost::shared_ptr<openni_wrapper::DepthImage> depth_image, void* cookie);
00127
00129 void
00130 irCallback (boost::shared_ptr<openni_wrapper::IRImage> ir_image, void* cookie);
00131
00133 void
00134 imageDepthImageCallback (const boost::shared_ptr<openni_wrapper::Image> &image,
00135 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image);
00136
00138 void
00139 irDepthImageCallback (const boost::shared_ptr<openni_wrapper::IRImage> &image,
00140 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image);
00141
00143 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ> >
00144 convertToXYZPointCloud (const boost::shared_ptr<openni_wrapper::DepthImage> &depth) const;
00145
00147 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZRGB> >
00148 convertToXYZRGBPointCloud (const boost::shared_ptr<openni_wrapper::Image> &image,
00149 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image) const;
00150
00152 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZRGBA> >
00153 convertToXYZRGBAPointCloud (const boost::shared_ptr<openni_wrapper::Image> &image,
00154 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image) const;
00155
00157 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> >
00158 convertToXYZIPointCloud (const boost::shared_ptr<openni_wrapper::IRImage> &image,
00159 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image) const;
00160
00162 Synchronizer<boost::shared_ptr<openni_wrapper::Image>, boost::shared_ptr<openni_wrapper::DepthImage> > rgb_sync_;
00163
00165 Synchronizer<boost::shared_ptr<openni_wrapper::IRImage>, boost::shared_ptr<openni_wrapper::DepthImage> > ir_sync_;
00166
00168 boost::shared_ptr<openni_wrapper::DeviceONI> device_;
00169 std::string rgb_frame_id_;
00170 std::string depth_frame_id_;
00171 bool running_;
00172 unsigned image_width_;
00173 unsigned image_height_;
00174 unsigned depth_width_;
00175 unsigned depth_height_;
00176 openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle;
00177 openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle;
00178 openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle;
00179 boost::signals2::signal<sig_cb_openni_image >* image_signal_;
00180 boost::signals2::signal<sig_cb_openni_depth_image >* depth_image_signal_;
00181 boost::signals2::signal<sig_cb_openni_ir_image >* ir_image_signal_;
00182 boost::signals2::signal<sig_cb_openni_image_depth_image>* image_depth_image_signal_;
00183 boost::signals2::signal<sig_cb_openni_ir_depth_image>* ir_depth_image_signal_;
00184 boost::signals2::signal<sig_cb_openni_point_cloud >* point_cloud_signal_;
00185 boost::signals2::signal<sig_cb_openni_point_cloud_i >* point_cloud_i_signal_;
00186 boost::signals2::signal<sig_cb_openni_point_cloud_rgb >* point_cloud_rgb_signal_;
00187 boost::signals2::signal<sig_cb_openni_point_cloud_rgba >* point_cloud_rgba_signal_;
00188
00189 public:
00190 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00191 };
00192
00193 }
00194
00195 #endif // __PCL_IO_ONI_PLAYER__
00196 #endif // HAVE_OPENNI
00197