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
00039
00040
00041 #ifndef PCL_APPS_IN_HAND_SCANNER_INPUT_DATA_PROCESSING_H
00042 #define PCL_APPS_IN_HAND_SCANNER_INPUT_DATA_PROCESSING_H
00043
00044 #include <pcl/pcl_exports.h>
00045 #include <pcl/apps/in_hand_scanner/eigen.h>
00046 #include <pcl/apps/in_hand_scanner/common_types.h>
00047 #include <pcl/apps/in_hand_scanner/utils.h>
00048
00050
00052
00053 namespace pcl
00054 {
00055 template <class PointInT, class PointOutT>
00056 class IntegralImageNormalEstimation;
00057 }
00058
00060
00062
00063 namespace pcl
00064 {
00065 namespace ihs
00066 {
00071 class PCL_EXPORTS InputDataProcessing
00072 {
00073 public:
00074
00075 typedef pcl::PointXYZRGBA PointXYZRGBA;
00076 typedef pcl::PointCloud <PointXYZRGBA> CloudXYZRGBA;
00077 typedef CloudXYZRGBA::Ptr CloudXYZRGBAPtr;
00078 typedef CloudXYZRGBA::ConstPtr CloudXYZRGBAConstPtr;
00079
00080 typedef pcl::PointXYZRGBNormal PointXYZRGBNormal;
00081 typedef pcl::PointCloud <PointXYZRGBNormal> CloudXYZRGBNormal;
00082 typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr;
00083 typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr;
00084
00086 InputDataProcessing ();
00087
00095 bool
00096 segment (const CloudXYZRGBAConstPtr& cloud_in,
00097 CloudXYZRGBNormalPtr& cloud_out,
00098 CloudXYZRGBNormalPtr& cloud_discarded) const;
00099
00106 bool
00107 calculateNormals (const CloudXYZRGBAConstPtr& cloud_in,
00108 CloudXYZRGBNormalPtr& cloud_out) const;
00109
00112 inline void setXMin (const float x_min) {if (x_min < x_max_) x_min_ = x_min;}
00113 inline void setXMax (const float x_max) {if (x_max > x_min_) x_max_ = x_max;}
00114 inline void setYMin (const float y_min) {if (y_min < y_max_) y_min_ = y_min;}
00115 inline void setYMax (const float y_max) {if (y_max > y_min_) y_max_ = y_max;}
00116 inline void setZMin (const float z_min) {if (z_min < z_max_) z_min_ = z_min;}
00117 inline void setZMax (const float z_max) {if (z_max > z_min_) z_max_ = z_max;}
00118
00119 inline float getXMin () const {return (x_min_);}
00120 inline float getXMax () const {return (x_max_);}
00121 inline float getYMin () const {return (y_min_);}
00122 inline float getYMax () const {return (y_max_);}
00123 inline float getZMin () const {return (z_min_);}
00124 inline float getZMax () const {return (z_max_);}
00131 inline void setHMin (const float h_min) {h_min_ = pcl::ihs::clamp (h_min, 0.f, 360.f);}
00132 inline void setHMax (const float h_max) {h_max_ = pcl::ihs::clamp (h_max, 0.f, 360.f);}
00133 inline void setSMin (const float s_min) {s_min_ = pcl::ihs::clamp (s_min, 0.f, 1.f);}
00134 inline void setSMax (const float s_max) {s_max_ = pcl::ihs::clamp (s_max, 0.f, 1.f);}
00135 inline void setVMin (const float v_min) {v_min_ = pcl::ihs::clamp (v_min, 0.f, 1.f);}
00136 inline void setVMax (const float v_max) {v_max_ = pcl::ihs::clamp (v_max, 0.f, 1.f);}
00137
00138 inline float getHMin () const {return (h_min_);}
00139 inline float getHMax () const {return (h_max_);}
00140 inline float getSMin () const {return (s_min_);}
00141 inline float getSMax () const {return (s_max_);}
00142 inline float getVMin () const {return (v_min_);}
00143 inline float getVMax () const {return (v_max_);}
00148 inline void setColorSegmentationInverted (const bool hsv_inverted) {hsv_inverted_ = hsv_inverted;}
00149 inline bool getColorSegmentationInverted () const {return (hsv_inverted_);}
00154 inline void setColorSegmentationEnabled (const bool hsv_enabled) {hsv_enabled_ = hsv_enabled;}
00155 inline bool getColorSegmentationEnabled () const {return (hsv_enabled_);}
00160 inline void setXYZErodeSize (const unsigned int size) {size_erode_ = size;}
00161 inline unsigned int getXYZErodeSize () const {return (size_erode_);}
00166 inline void setHSVDilateSize (const unsigned int size) {size_dilate_ = size;}
00167 inline unsigned int getHSVDilateSize () const {return (size_dilate_);}
00170 private:
00171
00172 typedef pcl::Normal Normal;
00173 typedef pcl::PointCloud <Normal> CloudNormals;
00174 typedef boost::shared_ptr <CloudNormals> CloudNormalsPtr;
00175 typedef boost::shared_ptr <const CloudNormals> CloudNormalsConstPtr;
00176
00177 typedef pcl::IntegralImageNormalEstimation <PointXYZRGBA, Normal> NormalEstimation;
00178 typedef boost::shared_ptr <NormalEstimation> NormalEstimationPtr;
00179 typedef boost::shared_ptr <const NormalEstimation> NormalEstimationConstPtr;
00180
00181 typedef Eigen::Matrix <bool, Eigen::Dynamic, Eigen::Dynamic> MatrixXb;
00182 typedef Eigen::MatrixXi MatrixXi;
00183
00187 void
00188 erode (MatrixXb& mask, const int k) const;
00189
00193 void
00194 dilate (MatrixXb& mask, const int k) const;
00195
00202 MatrixXi
00203 manhattan (const MatrixXb& mat, const bool comp) const;
00204
00206 void
00207 RGBToHSV (const unsigned char r,
00208 const unsigned char g,
00209 const unsigned char b,
00210 float& h,
00211 float& s,
00212 float& v) const;
00213
00215
00217
00218 NormalEstimationPtr normal_estimation_;
00219
00220 float x_min_;
00221 float x_max_;
00222 float y_min_;
00223 float y_max_;
00224 float z_min_;
00225 float z_max_;
00226
00227 float h_min_;
00228 float h_max_;
00229 float s_min_;
00230 float s_max_;
00231 float v_min_;
00232 float v_max_;
00233
00234 bool hsv_inverted_;
00235 bool hsv_enabled_;
00236
00237 unsigned int size_dilate_;
00238 unsigned int size_erode_;
00239 };
00240 }
00241 }
00242
00243 #endif // PCL_APPS_IN_HAND_SCANNER_INPUT_DATA_PROCESSING_H