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 #ifndef PCL_FILTERS_VOXEL_GRID_MAP_H_
00041 #define PCL_FILTERS_VOXEL_GRID_MAP_H_
00042 
00043 #include <pcl/filters/boost.h>
00044 #include <pcl/filters/filter.h>
00045 #include <map>
00046 
00047 namespace pcl
00048 {
00057   PCL_EXPORTS void 
00058   getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
00059                Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt);
00060 
00075   PCL_EXPORTS void 
00076   getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
00077                const std::string &distance_field_name, float min_distance, float max_distance, 
00078                Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative = false);
00079 
00084   inline Eigen::MatrixXi
00085   getHalfNeighborCellIndices ()
00086   {
00087     Eigen::MatrixXi relative_coordinates (3, 13);
00088     int idx = 0;
00089 
00090     
00091     for (int i = -1; i < 2; i++) 
00092     {
00093       for (int j = -1; j < 2; j++) 
00094       {
00095         relative_coordinates (0, idx) = i;
00096         relative_coordinates (1, idx) = j;
00097         relative_coordinates (2, idx) = -1;
00098         idx++;
00099       }
00100     }
00101     
00102     for (int i = -1; i < 2; i++) 
00103     {
00104       relative_coordinates (0, idx) = i;
00105       relative_coordinates (1, idx) = -1;
00106       relative_coordinates (2, idx) = 0;
00107       idx++;
00108     }
00109     
00110     relative_coordinates (0, idx) = -1;
00111     relative_coordinates (1, idx) = 0;
00112     relative_coordinates (2, idx) = 0;
00113 
00114     return (relative_coordinates);
00115   }
00116 
00121   inline Eigen::MatrixXi
00122   getAllNeighborCellIndices ()
00123   {
00124     Eigen::MatrixXi relative_coordinates = getHalfNeighborCellIndices ();
00125     Eigen::MatrixXi relative_coordinates_all( 3, 26);
00126     relative_coordinates_all.block<3, 13> (0, 0) = relative_coordinates;
00127     relative_coordinates_all.block<3, 13> (0, 13) = -relative_coordinates;
00128     return (relative_coordinates_all);
00129   }
00130 
00142   template <typename PointT> void 
00143   getMinMax3D (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00144                const std::string &distance_field_name, float min_distance, float max_distance,
00145                Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative = false);
00146 
00159   template <typename PointT> void 
00160   getMinMax3D (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00161                const std::vector<int> &indices,
00162                const std::string &distance_field_name, float min_distance, float max_distance,
00163                Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative = false);
00164 
00177   template <typename PointT>
00178   class VoxelGrid: public Filter<PointT>
00179   {
00180     protected:
00181       using Filter<PointT>::filter_name_;
00182       using Filter<PointT>::getClassName;
00183       using Filter<PointT>::input_;
00184       using Filter<PointT>::indices_;
00185 
00186       typedef typename Filter<PointT>::PointCloud PointCloud;
00187       typedef typename PointCloud::Ptr PointCloudPtr;
00188       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00189       typedef boost::shared_ptr< VoxelGrid<PointT> > Ptr;
00190       typedef boost::shared_ptr< const VoxelGrid<PointT> > ConstPtr;
00191  
00192 
00193     public:
00195       VoxelGrid () : 
00196         leaf_size_ (Eigen::Vector4f::Zero ()),
00197         inverse_leaf_size_ (Eigen::Array4f::Zero ()),
00198         downsample_all_data_ (true), 
00199         save_leaf_layout_ (false),
00200         leaf_layout_ (),
00201         min_b_ (Eigen::Vector4i::Zero ()),
00202         max_b_ (Eigen::Vector4i::Zero ()),
00203         div_b_ (Eigen::Vector4i::Zero ()),
00204         divb_mul_ (Eigen::Vector4i::Zero ()),
00205         filter_field_name_ (""), 
00206         filter_limit_min_ (-FLT_MAX), 
00207         filter_limit_max_ (FLT_MAX),
00208         filter_limit_negative_ (false)
00209       {
00210         filter_name_ = "VoxelGrid";
00211       }
00212 
00214       virtual ~VoxelGrid ()
00215       {
00216       }
00217 
00221       inline void 
00222       setLeafSize (const Eigen::Vector4f &leaf_size) 
00223       { 
00224         leaf_size_ = leaf_size; 
00225         
00226         if (leaf_size_[3] == 0)
00227           leaf_size_[3] = 1;
00228         
00229         inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array ();
00230       }
00231 
00237       inline void
00238       setLeafSize (float lx, float ly, float lz)
00239       {
00240         leaf_size_[0] = lx; leaf_size_[1] = ly; leaf_size_[2] = lz;
00241         
00242         if (leaf_size_[3] == 0)
00243           leaf_size_[3] = 1;
00244         
00245         inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array ();
00246       }
00247 
00249       inline Eigen::Vector3f 
00250       getLeafSize () { return (leaf_size_.head<3> ()); }
00251 
00255       inline void 
00256       setDownsampleAllData (bool downsample) { downsample_all_data_ = downsample; }
00257 
00261       inline bool 
00262       getDownsampleAllData () { return (downsample_all_data_); }
00263 
00267       inline void 
00268       setSaveLeafLayout (bool save_leaf_layout) { save_leaf_layout_ = save_leaf_layout; }
00269 
00271       inline bool 
00272       getSaveLeafLayout () { return (save_leaf_layout_); }
00273 
00277       inline Eigen::Vector3i 
00278       getMinBoxCoordinates () { return (min_b_.head<3> ()); }
00279 
00283       inline Eigen::Vector3i 
00284       getMaxBoxCoordinates () { return (max_b_.head<3> ()); }
00285 
00289       inline Eigen::Vector3i 
00290       getNrDivisions () { return (div_b_.head<3> ()); }
00291 
00295       inline Eigen::Vector3i 
00296       getDivisionMultiplier () { return (divb_mul_.head<3> ()); }
00297 
00306       inline int 
00307       getCentroidIndex (const PointT &p)
00308       {
00309         return (leaf_layout_.at ((Eigen::Vector4i (static_cast<int> (floor (p.x * inverse_leaf_size_[0])), 
00310                                                    static_cast<int> (floor (p.y * inverse_leaf_size_[1])), 
00311                                                    static_cast<int> (floor (p.z * inverse_leaf_size_[2])), 0) - min_b_).dot (divb_mul_)));
00312       }
00313 
00320       inline std::vector<int> 
00321       getNeighborCentroidIndices (const PointT &reference_point, const Eigen::MatrixXi &relative_coordinates)
00322       {
00323         Eigen::Vector4i ijk (static_cast<int> (floor (reference_point.x * inverse_leaf_size_[0])), 
00324                              static_cast<int> (floor (reference_point.y * inverse_leaf_size_[1])), 
00325                              static_cast<int> (floor (reference_point.z * inverse_leaf_size_[2])), 0);
00326         Eigen::Array4i diff2min = min_b_ - ijk;
00327         Eigen::Array4i diff2max = max_b_ - ijk;
00328         std::vector<int> neighbors (relative_coordinates.cols());
00329         for (int ni = 0; ni < relative_coordinates.cols (); ni++)
00330         {
00331           Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished();
00332           
00333           if ((diff2min <= displacement.array()).all() && (diff2max >= displacement.array()).all())
00334             neighbors[ni] = leaf_layout_[((ijk + displacement - min_b_).dot (divb_mul_))]; 
00335           else
00336             neighbors[ni] = -1; 
00337         }
00338         return (neighbors);
00339       }
00340 
00344       inline std::vector<int> 
00345       getLeafLayout () { return (leaf_layout_); }
00346 
00352       inline Eigen::Vector3i 
00353       getGridCoordinates (float x, float y, float z) 
00354       { 
00355         return (Eigen::Vector3i (static_cast<int> (floor (x * inverse_leaf_size_[0])), 
00356                                  static_cast<int> (floor (y * inverse_leaf_size_[1])), 
00357                                  static_cast<int> (floor (z * inverse_leaf_size_[2])))); 
00358       }
00359 
00363       inline int 
00364       getCentroidIndexAt (const Eigen::Vector3i &ijk)
00365       {
00366         int idx = ((Eigen::Vector4i() << ijk, 0).finished() - min_b_).dot (divb_mul_);
00367         if (idx < 0 || idx >= static_cast<int> (leaf_layout_.size ())) 
00368         {
00369           
00370           
00371           return (-1);
00372         }
00373         return (leaf_layout_[idx]);
00374       }
00375 
00380       inline void
00381       setFilterFieldName (const std::string &field_name)
00382       {
00383         filter_field_name_ = field_name;
00384       }
00385 
00387       inline std::string const
00388       getFilterFieldName ()
00389       {
00390         return (filter_field_name_);
00391       }
00392 
00397       inline void
00398       setFilterLimits (const double &limit_min, const double &limit_max)
00399       {
00400         filter_limit_min_ = limit_min;
00401         filter_limit_max_ = limit_max;
00402       }
00403 
00408       inline void
00409       getFilterLimits (double &limit_min, double &limit_max)
00410       {
00411         limit_min = filter_limit_min_;
00412         limit_max = filter_limit_max_;
00413       }
00414 
00419       inline void
00420       setFilterLimitsNegative (const bool limit_negative)
00421       {
00422         filter_limit_negative_ = limit_negative;
00423       }
00424 
00428       inline void
00429       getFilterLimitsNegative (bool &limit_negative)
00430       {
00431         limit_negative = filter_limit_negative_;
00432       }
00433 
00437       inline bool
00438       getFilterLimitsNegative ()
00439       {
00440         return (filter_limit_negative_);
00441       }
00442 
00443     protected:
00445       Eigen::Vector4f leaf_size_;
00446 
00448       Eigen::Array4f inverse_leaf_size_;
00449 
00451       bool downsample_all_data_;
00452 
00454       bool save_leaf_layout_;
00455 
00457       std::vector<int> leaf_layout_;
00458 
00460       Eigen::Vector4i min_b_, max_b_, div_b_, divb_mul_;
00461 
00463       std::string filter_field_name_;
00464 
00466       double filter_limit_min_;
00467 
00469       double filter_limit_max_;
00470 
00472       bool filter_limit_negative_;
00473 
00474       typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00475 
00479       void 
00480       applyFilter (PointCloud &output);
00481   };
00482 
00495   template <>
00496   class PCL_EXPORTS VoxelGrid<pcl::PCLPointCloud2> : public Filter<pcl::PCLPointCloud2>
00497   {
00498     using Filter<pcl::PCLPointCloud2>::filter_name_;
00499     using Filter<pcl::PCLPointCloud2>::getClassName;
00500 
00501     typedef pcl::PCLPointCloud2 PCLPointCloud2;
00502     typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr;
00503     typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr;
00504 
00505     public:
00507       VoxelGrid () : 
00508         leaf_size_ (Eigen::Vector4f::Zero ()),
00509         inverse_leaf_size_ (Eigen::Array4f::Zero ()),
00510         downsample_all_data_ (true), 
00511         save_leaf_layout_ (false),
00512         leaf_layout_ (),
00513         min_b_ (Eigen::Vector4i::Zero ()),
00514         max_b_ (Eigen::Vector4i::Zero ()),
00515         div_b_ (Eigen::Vector4i::Zero ()),
00516         divb_mul_ (Eigen::Vector4i::Zero ()),
00517         filter_field_name_ (""), 
00518         filter_limit_min_ (-FLT_MAX), 
00519         filter_limit_max_ (FLT_MAX),
00520         filter_limit_negative_ (false)
00521       {
00522         filter_name_ = "VoxelGrid";
00523       }
00524 
00526       virtual ~VoxelGrid ()
00527       {
00528       }
00529 
00533       inline void 
00534       setLeafSize (const Eigen::Vector4f &leaf_size) 
00535       { 
00536         leaf_size_ = leaf_size; 
00537         
00538         if (leaf_size_[3] == 0)
00539           leaf_size_[3] = 1;
00540         
00541         inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array ();
00542       }
00543 
00549       inline void
00550       setLeafSize (float lx, float ly, float lz)
00551       {
00552         leaf_size_[0] = lx; leaf_size_[1] = ly; leaf_size_[2] = lz;
00553         
00554         if (leaf_size_[3] == 0)
00555           leaf_size_[3] = 1;
00556         
00557         inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array ();
00558       }
00559 
00561       inline Eigen::Vector3f 
00562       getLeafSize () { return (leaf_size_.head<3> ()); }
00563 
00567       inline void 
00568       setDownsampleAllData (bool downsample) { downsample_all_data_ = downsample; }
00569 
00573       inline bool 
00574       getDownsampleAllData () { return (downsample_all_data_); }
00575 
00579       inline void 
00580       setSaveLeafLayout (bool save_leaf_layout) { save_leaf_layout_ = save_leaf_layout; }
00581 
00583       inline bool 
00584       getSaveLeafLayout () { return (save_leaf_layout_); }
00585 
00589       inline Eigen::Vector3i 
00590       getMinBoxCoordinates () { return (min_b_.head<3> ()); }
00591 
00595       inline Eigen::Vector3i 
00596       getMaxBoxCoordinates () { return (max_b_.head<3> ()); }
00597 
00601       inline Eigen::Vector3i 
00602       getNrDivisions () { return (div_b_.head<3> ()); }
00603 
00607       inline Eigen::Vector3i 
00608       getDivisionMultiplier () { return (divb_mul_.head<3> ()); }
00609 
00617       inline int 
00618       getCentroidIndex (float x, float y, float z)
00619       {
00620         return (leaf_layout_.at ((Eigen::Vector4i (static_cast<int> (floor (x * inverse_leaf_size_[0])), 
00621                                                    static_cast<int> (floor (y * inverse_leaf_size_[1])), 
00622                                                    static_cast<int> (floor (z * inverse_leaf_size_[2])), 
00623                                                    0) 
00624                 - min_b_).dot (divb_mul_)));
00625       }
00626 
00635       inline std::vector<int> 
00636       getNeighborCentroidIndices (float x, float y, float z, const Eigen::MatrixXi &relative_coordinates)
00637       {
00638         Eigen::Vector4i ijk (static_cast<int> (floor (x * inverse_leaf_size_[0])), 
00639                              static_cast<int> (floor (y * inverse_leaf_size_[1])), 
00640                              static_cast<int> (floor (z * inverse_leaf_size_[2])), 0);
00641         Eigen::Array4i diff2min = min_b_ - ijk;
00642         Eigen::Array4i diff2max = max_b_ - ijk;
00643         std::vector<int> neighbors (relative_coordinates.cols());
00644         for (int ni = 0; ni < relative_coordinates.cols (); ni++)
00645         {
00646           Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished();
00647           
00648           if ((diff2min <= displacement.array()).all() && (diff2max >= displacement.array()).all())
00649             neighbors[ni] = leaf_layout_[((ijk + displacement - min_b_).dot (divb_mul_))]; 
00650           else
00651             neighbors[ni] = -1; 
00652         }
00653         return (neighbors);
00654       }
00655       
00664       inline std::vector<int> 
00665       getNeighborCentroidIndices (float x, float y, float z, const std::vector<Eigen::Vector3i> &relative_coordinates)
00666       {
00667         Eigen::Vector4i ijk (static_cast<int> (floorf (x * inverse_leaf_size_[0])), static_cast<int> (floorf (y * inverse_leaf_size_[1])), static_cast<int> (floorf (z * inverse_leaf_size_[2])), 0);
00668         std::vector<int> neighbors;
00669         neighbors.reserve (relative_coordinates.size ());
00670         for (std::vector<Eigen::Vector3i>::const_iterator it = relative_coordinates.begin (); it != relative_coordinates.end (); it++)
00671           neighbors.push_back (leaf_layout_[(ijk + (Eigen::Vector4i() << *it, 0).finished() - min_b_).dot (divb_mul_)]);
00672         return (neighbors);
00673       }
00674 
00678       inline std::vector<int> 
00679       getLeafLayout () { return (leaf_layout_); }
00680 
00686       inline Eigen::Vector3i 
00687       getGridCoordinates (float x, float y, float z) 
00688       { 
00689         return (Eigen::Vector3i (static_cast<int> (floor (x * inverse_leaf_size_[0])), 
00690                                  static_cast<int> (floor (y * inverse_leaf_size_[1])), 
00691                                  static_cast<int> (floor (z * inverse_leaf_size_[2])))); 
00692       }
00693 
00697       inline int 
00698       getCentroidIndexAt (const Eigen::Vector3i &ijk)
00699       {
00700         int idx = ((Eigen::Vector4i() << ijk, 0).finished() - min_b_).dot (divb_mul_);
00701         if (idx < 0 || idx >= static_cast<int> (leaf_layout_.size ())) 
00702         {
00703           
00704           
00705           return (-1);
00706         }
00707         return (leaf_layout_[idx]);
00708       }
00709 
00714       inline void
00715       setFilterFieldName (const std::string &field_name)
00716       {
00717         filter_field_name_ = field_name;
00718       }
00719 
00721       inline std::string const
00722       getFilterFieldName ()
00723       {
00724         return (filter_field_name_);
00725       }
00726 
00731       inline void
00732       setFilterLimits (const double &limit_min, const double &limit_max)
00733       {
00734         filter_limit_min_ = limit_min;
00735         filter_limit_max_ = limit_max;
00736       }
00737 
00742       inline void
00743       getFilterLimits (double &limit_min, double &limit_max)
00744       {
00745         limit_min = filter_limit_min_;
00746         limit_max = filter_limit_max_;
00747       }
00748 
00753       inline void
00754       setFilterLimitsNegative (const bool limit_negative)
00755       {
00756         filter_limit_negative_ = limit_negative;
00757       }
00758 
00762       inline void
00763       getFilterLimitsNegative (bool &limit_negative)
00764       {
00765         limit_negative = filter_limit_negative_;
00766       }
00767 
00771       inline bool
00772       getFilterLimitsNegative ()
00773       {
00774         return (filter_limit_negative_);
00775       }
00776 
00777     protected:
00779       Eigen::Vector4f leaf_size_;
00780 
00782       Eigen::Array4f inverse_leaf_size_;
00783 
00785       bool downsample_all_data_;
00786 
00790       bool save_leaf_layout_;
00791 
00795       std::vector<int> leaf_layout_;
00796 
00800       Eigen::Vector4i min_b_, max_b_, div_b_, divb_mul_;
00801 
00803       std::string filter_field_name_;
00804 
00806       double filter_limit_min_;
00807 
00809       double filter_limit_max_;
00810 
00812       bool filter_limit_negative_;
00813 
00817       void 
00818       applyFilter (PCLPointCloud2 &output);
00819   };
00820 }
00821 
00822 #ifdef PCL_NO_PRECOMPILE
00823 #include <pcl/filters/impl/voxel_grid.hpp>
00824 #endif
00825 
00826 #endif  //#ifndef PCL_FILTERS_VOXEL_GRID_MAP_H_