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 #ifndef PCL_FILTERS_VOXEL_GRID_MAP_H_
00039 #define PCL_FILTERS_VOXEL_GRID_MAP_H_
00040
00041 #include "pcl/filters/filter.h"
00042 #include <map>
00043 #include <boost/mpl/size.hpp>
00044 #include <boost/fusion/sequence/intrinsic/at_key.hpp>
00045
00046 namespace pcl
00047 {
00048 void
00049 getMinMax3D (const sensor_msgs::PointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
00050 Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt);
00051
00052 void
00053 getMinMax3D (const sensor_msgs::PointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
00054 const std::string &distance_field_name, float min_distance, float max_distance,
00055 Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative = false);
00056
00067 template <typename PointT> void
00068 getMinMax3D (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00069 const std::string &distance_field_name, float min_distance, float max_distance,
00070 Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative = false);
00071
00073
00074 template <typename PointT>
00075 struct NdCopyEigenPointFunctor
00076 {
00077 typedef typename traits::POD<PointT>::type Pod;
00078
00079 NdCopyEigenPointFunctor (const Eigen::VectorXf &p1, PointT &p2)
00080 : p1_ (p1),
00081 p2_ (reinterpret_cast<Pod&>(p2)),
00082 f_idx_ (0) { }
00083
00084 template<typename Key> inline void operator() ()
00085 {
00086
00087 typedef typename pcl::traits::datatype<PointT, Key>::type T;
00088 uint8_t* data_ptr = reinterpret_cast<uint8_t*>(&p2_) + pcl::traits::offset<PointT, Key>::value;
00089 *reinterpret_cast<T*>(data_ptr) = p1_[f_idx_++];
00090 }
00091
00092 private:
00093 const Eigen::VectorXf &p1_;
00094 Pod &p2_;
00095 int f_idx_;
00096 };
00097
00099 template <typename PointT>
00100 struct NdCopyPointEigenFunctor
00101 {
00102 typedef typename traits::POD<PointT>::type Pod;
00103
00104 NdCopyPointEigenFunctor (const PointT &p1, Eigen::VectorXf &p2)
00105 : p1_ (reinterpret_cast<const Pod&>(p1)), p2_ (p2), f_idx_ (0) { }
00106
00107 template<typename Key> inline void operator() ()
00108 {
00109
00110 typedef typename pcl::traits::datatype<PointT, Key>::type T;
00111 const uint8_t* data_ptr = reinterpret_cast<const uint8_t*>(&p1_) + pcl::traits::offset<PointT, Key>::value;
00112 p2_[f_idx_++] = *reinterpret_cast<const T*>(data_ptr);
00113 }
00114
00115 private:
00116 const Pod &p1_;
00117 Eigen::VectorXf &p2_;
00118 int f_idx_;
00119 };
00120
00124 template <typename PointT>
00125 class VoxelGrid: public Filter<PointT>
00126 {
00127 using Filter<PointT>::filter_name_;
00128 using Filter<PointT>::getClassName;
00129 using Filter<PointT>::input_;
00130 using Filter<PointT>::indices_;
00131 using Filter<PointT>::filter_limit_negative_;
00132 using Filter<PointT>::filter_limit_min_;
00133 using Filter<PointT>::filter_limit_max_;
00134 using Filter<PointT>::filter_field_name_;
00135
00136 typedef typename Filter<PointT>::PointCloud PointCloud;
00137 typedef typename PointCloud::Ptr PointCloudPtr;
00138 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00139
00140 public:
00142 VoxelGrid () : downsample_all_data_ (true), save_leaf_layout_ (false)
00143 {
00144 leaf_size_.setZero ();
00145 min_b_.setZero ();
00146 max_b_.setZero ();
00147 filter_name_ = "VoxelGrid";
00148 }
00149
00153 inline void
00154 setLeafSize (const Eigen::Vector4f &leaf_size) { leaf_size_ = leaf_size; }
00155
00161 inline void
00162 setLeafSize (float lx, float ly, float lz)
00163 {
00164 leaf_size_[0] = lx; leaf_size_[1] = ly; leaf_size_[2] = lz;
00165 }
00166
00168 inline Eigen::Vector3f
00169 getLeafSize () { return (leaf_size_.head<3> ()); }
00170
00174 inline void
00175 setDownsampleAllData (bool downsample) { downsample_all_data_ = downsample; }
00176
00179 inline bool
00180 getDownsampleAllData () { return (downsample_all_data_); }
00181
00185 inline void
00186 setSaveLeafLayout (bool save_leaf_layout) { save_leaf_layout_ = save_leaf_layout; }
00187
00189 inline bool
00190 getSaveLeafLayout () { return (save_leaf_layout_); }
00191
00193 inline Eigen::Vector3i
00194 getMinBoxCoordinates () { return (min_b_.head<3> ()); }
00195
00197 inline Eigen::Vector3i
00198 getMaxBoxCoordinates () { return (max_b_.head<3> ()); }
00199
00201 inline Eigen::Vector3i
00202 getNrDivisions () { return (div_b_.head<3> ()); }
00203
00205 inline Eigen::Vector3i
00206 getDivisionMultiplier () { return (divb_mul_.head<3> ()); }
00207
00212 inline int
00213 getCentroidIndex (PointT p)
00214 {
00215 return leaf_layout_.at ((Eigen::Vector4i (floor (p.x / leaf_size_[0]), floor (p.y / leaf_size_[1]), floor (p.z / leaf_size_[2]), 0) - min_b_).dot (divb_mul_));
00216 }
00217
00224 inline std::vector<int>
00225 getNeighborCentroidIndices (PointT reference_point, Eigen::MatrixXi relative_coordinates)
00226 {
00227 Eigen::Vector4i ijk (floor (reference_point.x / leaf_size_[0]), floor (reference_point.y / leaf_size_[1]), floor (reference_point.z / leaf_size_[2]), 0);
00228 Eigen::Array4i diff2min = min_b_ - ijk;
00229 Eigen::Array4i diff2max = max_b_ - ijk;
00230 std::vector<int> neighbors (relative_coordinates.cols());
00231 for (int ni = 0; ni < relative_coordinates.cols (); ni++)
00232 {
00233 Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished();
00234
00235 if ((diff2min <= displacement.array()).all() && (diff2max >= displacement.array()).all())
00236 neighbors[ni] = leaf_layout_[((ijk + displacement - min_b_).dot (divb_mul_))];
00237 else
00238 neighbors[ni] = -1;
00239 }
00240 return neighbors;
00241 }
00242
00246 inline std::vector<int>
00247 getLeafLayout () { return (leaf_layout_); }
00248
00250 inline Eigen::Vector3i
00251 getGridCoordinates (float x, float y, float z)
00252 {
00253 return Eigen::Vector3i (floor (x / leaf_size_[0]), floor (y / leaf_size_[1]), floor (z / leaf_size_[2]));
00254 }
00255
00257 inline int
00258 getCentroidIndexAt (Eigen::Vector3i ijk, bool verbose = true)
00259 {
00260 int idx = ((Eigen::Vector4i() << ijk, 0).finished() - min_b_).dot (divb_mul_);
00261 if (idx < 0 || idx >= (int)leaf_layout_.size ())
00262 {
00263 if (verbose)
00264 ROS_ERROR ("[pcl::%s::getCentroidIndexAt] Specified coordinate is outside grid bounds, or leaf layout is not saved, make sure to call setSaveLeafLayout(true) and filter(output) first!", getClassName ().c_str ());
00265 return -1;
00266 }
00267 return leaf_layout_[idx];
00268 }
00269
00270 protected:
00272 struct Leaf
00273 {
00274 Leaf () : nr_points(0) {}
00275 Eigen::VectorXf centroid;
00276 int nr_points;
00277 };
00278
00280 std::map<size_t, Leaf> leaves_;
00281
00283 Eigen::Vector4f leaf_size_;
00284
00286 bool downsample_all_data_;
00287
00289 bool save_leaf_layout_;
00290
00292 std::vector<int> leaf_layout_;
00293
00295 Eigen::Vector4i min_b_, max_b_, div_b_, divb_mul_;
00296
00297 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00298
00302 void
00303 applyFilter (PointCloud &output);
00304 };
00305
00309 template <>
00310 class VoxelGrid<sensor_msgs::PointCloud2> : public Filter<sensor_msgs::PointCloud2>
00311 {
00312 using Filter<sensor_msgs::PointCloud2>::filter_name_;
00313 using Filter<sensor_msgs::PointCloud2>::getClassName;
00314
00315 typedef sensor_msgs::PointCloud2 PointCloud2;
00316 typedef PointCloud2::Ptr PointCloud2Ptr;
00317 typedef PointCloud2::ConstPtr PointCloud2ConstPtr;
00318
00319 public:
00321 VoxelGrid () : downsample_all_data_ (true), save_leaf_layout_ (false)
00322 {
00323 leaf_size_.setZero ();
00324 min_b_.setZero ();
00325 max_b_.setZero ();
00326 filter_name_ = "VoxelGrid";
00327 }
00328
00332 inline void
00333 setLeafSize (const Eigen::Vector4f &leaf_size) { leaf_size_ = leaf_size; }
00334
00340 inline void
00341 setLeafSize (float lx, float ly, float lz)
00342 {
00343 leaf_size_[0] = lx; leaf_size_[1] = ly; leaf_size_[2] = lz;
00344 }
00345
00347 inline Eigen::Vector3f
00348 getLeafSize () { return (leaf_size_.head<3> ()); }
00349
00353 inline void
00354 setDownsampleAllData (bool downsample) { downsample_all_data_ = downsample; }
00355
00358 inline bool
00359 getDownsampleAllData () { return (downsample_all_data_); }
00360
00364 inline void
00365 setSaveLeafLayout (bool save_leaf_layout) { save_leaf_layout_ = save_leaf_layout; }
00366
00368 inline bool
00369 getSaveLeafLayout () { return (save_leaf_layout_); }
00370
00372 inline Eigen::Vector3i
00373 getMinBoxCoordinates () { return (min_b_.head<3> ()); }
00374
00376 inline Eigen::Vector3i
00377 getMaxBoxCoordinates () { return (max_b_.head<3> ()); }
00378
00380 inline Eigen::Vector3i
00381 getNrDivisions () { return (div_b_.head<3> ()); }
00382
00384 inline Eigen::Vector3i
00385 getDivisionMultiplier () { return (divb_mul_.head<3> ()); }
00386
00391 inline int
00392 getCentroidIndex (float x, float y, float z)
00393 {
00394 return leaf_layout_.at ((Eigen::Vector4i (floor (x / leaf_size_[0]), floor (y / leaf_size_[1]), floor (z / leaf_size_[2]), 0) - min_b_).dot (divb_mul_));
00395 }
00396
00405 inline std::vector<int>
00406 getNeighborCentroidIndices (float x, float y, float z, Eigen::MatrixXi relative_coordinates)
00407 {
00408 Eigen::Vector4i ijk (floor (x / leaf_size_[0]), floor (y / leaf_size_[1]), floor (z / leaf_size_[2]), 0);
00409 Eigen::Array4i diff2min = min_b_ - ijk;
00410 Eigen::Array4i diff2max = max_b_ - ijk;
00411 std::vector<int> neighbors (relative_coordinates.cols());
00412 for (int ni = 0; ni < relative_coordinates.cols (); ni++)
00413 {
00414 Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished();
00415
00416 if ((diff2min <= displacement.array()).all() && (diff2max >= displacement.array()).all())
00417 neighbors[ni] = leaf_layout_[((ijk + displacement - min_b_).dot (divb_mul_))];
00418 else
00419 neighbors[ni] = -1;
00420 }
00421 return neighbors;
00422 }
00423
00424 inline std::vector<int>
00425 getNeighborCentroidIndices (float x, float y, float z, std::vector<Eigen::Vector3i> relative_coordinates)
00426 {
00427 Eigen::Vector4i ijk (floor (x / leaf_size_[0]), floor (y / leaf_size_[1]), floor (z / leaf_size_[2]), 0);
00428 std::vector<int> neighbors;
00429 neighbors.reserve (relative_coordinates.size ());
00430 for (std::vector<Eigen::Vector3i>::iterator it = relative_coordinates.begin (); it != relative_coordinates.end (); it++)
00431 neighbors.push_back (leaf_layout_[(ijk + (Eigen::Vector4i() << *it, 0).finished() - min_b_).dot (divb_mul_)]);
00432 return neighbors;
00433 }
00434
00438 inline std::vector<int>
00439 getLeafLayout () { return (leaf_layout_); }
00440
00442 inline Eigen::Vector3i
00443 getGridCoordinates (float x, float y, float z)
00444 {
00445 return Eigen::Vector3i (floor (x / leaf_size_[0]), floor (y / leaf_size_[1]), floor (z / leaf_size_[2]));
00446 }
00447
00449 inline int
00450 getCentroidIndexAt (Eigen::Vector3i ijk, bool verbose = true)
00451 {
00452 int idx = ((Eigen::Vector4i() << ijk, 0).finished() - min_b_).dot (divb_mul_);
00453 if (idx < 0 || idx >= (int)leaf_layout_.size ())
00454 {
00455 if (verbose)
00456 ROS_ERROR ("[pcl::%s::getCentroidIndexAt] Specified coordinate is outside grid bounds, or leaf layout is not saved, make sure to call setSaveLeafLayout(true) and filter(output) first!", getClassName ().c_str ());
00457 return -1;
00458 }
00459 return leaf_layout_[idx];
00460 }
00461
00462 protected:
00464 struct Leaf
00465 {
00466 Leaf () : nr_points(0) { }
00467 Eigen::VectorXf centroid;
00468 int nr_points;
00469 };
00470
00472 std::map<size_t, Leaf> leaves_;
00473
00475 Eigen::Vector4f leaf_size_;
00476
00478 bool downsample_all_data_;
00479
00481 bool save_leaf_layout_;
00482
00484 std::vector<int> leaf_layout_;
00485
00487 Eigen::Vector4i min_b_, max_b_, div_b_, divb_mul_;
00488
00492 void
00493 applyFilter (PointCloud2 &output);
00494 };
00495 }
00496
00497 #endif //#ifndef PCL_FILTERS_VOXEL_GRID_MAP_H_