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_ONI_PLAYER__
00042 #define __PCL_IO_ONI_PLAYER__
00043
00044 #include <pcl/io/eigen.h>
00045 #include <pcl/io/boost.h>
00046 #include <pcl/io/grabber.h>
00047 #include <pcl/io/openni_camera/openni_driver.h>
00048 #include <pcl/io/openni_camera/openni_device_oni.h>
00049 #include <pcl/io/openni_camera/openni_image.h>
00050 #include <pcl/io/openni_camera/openni_depth_image.h>
00051 #include <pcl/io/openni_camera/openni_ir_image.h>
00052 #include <string>
00053 #include <deque>
00054 #include <pcl/common/synchronizer.h>
00055
00056 namespace pcl
00057 {
00059 template <typename T> class PointCloud;
00061 struct PointXYZ;
00063 struct PointXYZRGB;
00065 struct PointXYZRGBA;
00067 struct PointXYZI;
00068
00073 class PCL_EXPORTS ONIGrabber : public Grabber
00074 {
00075 public:
00076
00077 typedef void (sig_cb_openni_image) (const boost::shared_ptr<openni_wrapper::Image>&);
00078 typedef void (sig_cb_openni_depth_image) (const boost::shared_ptr<openni_wrapper::DepthImage>&);
00079 typedef void (sig_cb_openni_ir_image) (const boost::shared_ptr<openni_wrapper::IRImage>&);
00080 typedef void (sig_cb_openni_image_depth_image) (const boost::shared_ptr<openni_wrapper::Image>&, const boost::shared_ptr<openni_wrapper::DepthImage>&, float constant) ;
00081 typedef void (sig_cb_openni_ir_depth_image) (const boost::shared_ptr<openni_wrapper::IRImage>&, const boost::shared_ptr<openni_wrapper::DepthImage>&, float constant) ;
00082 typedef void (sig_cb_openni_point_cloud) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZ> >&);
00083 typedef void (sig_cb_openni_point_cloud_rgb) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGB> >&);
00084 typedef void (sig_cb_openni_point_cloud_rgba) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGBA> >&);
00085 typedef void (sig_cb_openni_point_cloud_i) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZI> >&);
00086
00092 ONIGrabber (const std::string& file_name, bool repeat, bool stream);
00093
00095 virtual ~ONIGrabber () throw ();
00096
00100 virtual void
00101 start ();
00102
00106 virtual void
00107 stop ();
00108
00112 virtual std::string
00113 getName () const;
00114
00118 virtual bool
00119 isRunning () const;
00120
00122 virtual float
00123 getFramesPerSecond () const;
00124
00126 inline bool
00127 hasDataLeft ()
00128 {
00129 return (device_->hasDataLeft ());
00130 }
00131
00132 protected:
00134 void
00135 imageCallback (boost::shared_ptr<openni_wrapper::Image> image, void* cookie);
00136
00138 void
00139 depthCallback (boost::shared_ptr<openni_wrapper::DepthImage> depth_image, void* cookie);
00140
00142 void
00143 irCallback (boost::shared_ptr<openni_wrapper::IRImage> ir_image, void* cookie);
00144
00146 void
00147 imageDepthImageCallback (const boost::shared_ptr<openni_wrapper::Image> &image,
00148 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image);
00149
00151 void
00152 irDepthImageCallback (const boost::shared_ptr<openni_wrapper::IRImage> &image,
00153 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image);
00154
00156 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ> >
00157 convertToXYZPointCloud (const boost::shared_ptr<openni_wrapper::DepthImage> &depth) const;
00158
00160 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZRGB> >
00161 convertToXYZRGBPointCloud (const boost::shared_ptr<openni_wrapper::Image> &image,
00162 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image) const;
00163
00165 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZRGBA> >
00166 convertToXYZRGBAPointCloud (const boost::shared_ptr<openni_wrapper::Image> &image,
00167 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image) const;
00168
00170 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> >
00171 convertToXYZIPointCloud (const boost::shared_ptr<openni_wrapper::IRImage> &image,
00172 const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image) const;
00173
00175 Synchronizer<boost::shared_ptr<openni_wrapper::Image>, boost::shared_ptr<openni_wrapper::DepthImage> > rgb_sync_;
00176
00178 Synchronizer<boost::shared_ptr<openni_wrapper::IRImage>, boost::shared_ptr<openni_wrapper::DepthImage> > ir_sync_;
00179
00181 boost::shared_ptr<openni_wrapper::DeviceONI> device_;
00182 std::string rgb_frame_id_;
00183 std::string depth_frame_id_;
00184 bool running_;
00185 unsigned image_width_;
00186 unsigned image_height_;
00187 unsigned depth_width_;
00188 unsigned depth_height_;
00189 openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle;
00190 openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle;
00191 openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle;
00192 boost::signals2::signal<sig_cb_openni_image >* image_signal_;
00193 boost::signals2::signal<sig_cb_openni_depth_image >* depth_image_signal_;
00194 boost::signals2::signal<sig_cb_openni_ir_image >* ir_image_signal_;
00195 boost::signals2::signal<sig_cb_openni_image_depth_image>* image_depth_image_signal_;
00196 boost::signals2::signal<sig_cb_openni_ir_depth_image>* ir_depth_image_signal_;
00197 boost::signals2::signal<sig_cb_openni_point_cloud >* point_cloud_signal_;
00198 boost::signals2::signal<sig_cb_openni_point_cloud_i >* point_cloud_i_signal_;
00199 boost::signals2::signal<sig_cb_openni_point_cloud_rgb >* point_cloud_rgb_signal_;
00200 boost::signals2::signal<sig_cb_openni_point_cloud_rgba >* point_cloud_rgba_signal_;
00201
00202 public:
00203 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00204 };
00205
00206 }
00207
00208 #endif // __PCL_IO_ONI_PLAYER__
00209 #endif // HAVE_OPENNI
00210