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_FZAPI
00040
00041 #ifndef __PCL_IO_FOTONIC_GRABBER__
00042 #define __PCL_IO_FOTONIC_GRABBER__
00043
00044 #include <pcl/io/eigen.h>
00045 #include <pcl/io/boost.h>
00046 #include <pcl/io/grabber.h>
00047 #include <pcl/common/synchronizer.h>
00048
00049 #include <boost/thread.hpp>
00050
00051 #include <fz_api.h>
00052
00053 #include <string>
00054 #include <deque>
00055
00056 namespace pcl
00057 {
00058 struct PointXYZ;
00059 struct PointXYZRGB;
00060 struct PointXYZRGBA;
00061 struct PointXYZI;
00062 template <typename T> class PointCloud;
00063
00064
00069 class PCL_EXPORTS FotonicGrabber : public Grabber
00070 {
00071 public:
00072
00073 typedef enum
00074 {
00075 Fotonic_Default_Mode = 0,
00076 } Mode;
00077
00078
00079 typedef void (sig_cb_fotonic_point_cloud) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZ> >&);
00080 typedef void (sig_cb_fotonic_point_cloud_rgb) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGB> >&);
00081 typedef void (sig_cb_fotonic_point_cloud_rgba) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGBA> >&);
00082 typedef void (sig_cb_fotonic_point_cloud_i) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZI> >&);
00083
00084 public:
00090 FotonicGrabber (const FZ_DEVICE_INFO& device_info,
00091 const Mode& depth_mode = Fotonic_Default_Mode,
00092 const Mode& image_mode = Fotonic_Default_Mode);
00093
00095 virtual ~FotonicGrabber () throw ();
00096
00098 static void
00099 initAPI ();
00100
00102 static void
00103 exitAPI ();
00104
00106 static std::vector<FZ_DEVICE_INFO>
00107 enumDevices ();
00108
00110 virtual void
00111 start ();
00112
00114 virtual void
00115 stop ();
00116
00118 virtual bool
00119 isRunning () const;
00120
00121 virtual std::string
00122 getName () const;
00123
00125 virtual float
00126 getFramesPerSecond () const;
00127
00128 protected:
00129
00131 void
00132 onInit (const FZ_DEVICE_INFO& device_info, const Mode& depth_mode, const Mode& image_mode);
00133
00135 void
00136 setupDevice (const FZ_DEVICE_INFO& device_info, const Mode& depth_mode, const Mode& image_mode);
00137
00139 void
00140 processGrabbing ();
00141
00142 boost::signals2::signal<sig_cb_fotonic_point_cloud>* point_cloud_signal_;
00143
00144 boost::signals2::signal<sig_cb_fotonic_point_cloud_rgb>* point_cloud_rgb_signal_;
00145 boost::signals2::signal<sig_cb_fotonic_point_cloud_rgba>* point_cloud_rgba_signal_;
00146
00147 protected:
00148 bool running_;
00149
00150 FZ_Device_Handle_t * fotonic_device_handle_;
00151
00152 boost::thread grabber_thread_;
00153
00154 public:
00155 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00156 };
00157
00158 }
00159 #endif // __PCL_IO_FOTONIC_GRABBER__
00160 #endif // HAVE_FOTONIC