voxel_grid_covariance_omp_impl.hpp 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487
  1. /*
  2. * Software License Agreement (BSD License)
  3. *
  4. * Point Cloud Library (PCL) - www.pointclouds.org
  5. * Copyright (c) 2010-2011, Willow Garage, Inc.
  6. *
  7. * All rights reserved.
  8. *
  9. * Redistribution and use in source and binary forms, with or without
  10. * modification, are permitted provided that the following conditions
  11. * are met:
  12. *
  13. * * Redistributions of source code must retain the above copyright
  14. * notice, this list of conditions and the following disclaimer.
  15. * * Redistributions in binary form must reproduce the above
  16. * copyright notice, this list of conditions and the following
  17. * disclaimer in the documentation and/or other materials provided
  18. * with the distribution.
  19. * * Neither the name of the copyright holder(s) nor the names of its
  20. * contributors may be used to endorse or promote products derived
  21. * from this software without specific prior written permission.
  22. *
  23. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  24. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  25. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  26. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  27. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  28. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  29. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  30. * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  31. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  32. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  33. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  34. * POSSIBILITY OF SUCH DAMAGE.
  35. *
  36. */
  37. #ifndef PCL_VOXEL_GRID_COVARIANCE_IMPL_OMP_H_
  38. #define PCL_VOXEL_GRID_COVARIANCE_IMPL_OMP_H_
  39. #include <pcl/common/common.h>
  40. #include <pcl/filters/boost.h>
  41. #include "voxel_grid_covariance_omp.h"
  42. #include <Eigen/Dense>
  43. #include <Eigen/Cholesky>
  44. //////////////////////////////////////////////////////////////////////////////////////////
  45. template<typename PointT> void
  46. pclomp::VoxelGridCovariance<PointT>::applyFilter (PointCloud &output)
  47. {
  48. voxel_centroids_leaf_indices_.clear ();
  49. // Has the input dataset been set already?
  50. if (!input_)
  51. {
  52. PCL_WARN ("[pcl::%s::applyFilter] No input dataset given!\n", getClassName ().c_str ());
  53. output.width = output.height = 0;
  54. output.points.clear ();
  55. return;
  56. }
  57. // Copy the header (and thus the frame_id) + allocate enough space for points
  58. output.height = 1; // downsampling breaks the organized structure
  59. output.is_dense = true; // we filter out invalid points
  60. output.points.clear ();
  61. Eigen::Vector4f min_p, max_p;
  62. // Get the minimum and maximum dimensions
  63. if (!filter_field_name_.empty ()) // If we don't want to process the entire cloud...
  64. pcl::getMinMax3D<PointT> (input_, filter_field_name_, static_cast<float> (filter_limit_min_), static_cast<float> (filter_limit_max_), min_p, max_p, filter_limit_negative_);
  65. else
  66. pcl::getMinMax3D<PointT> (*input_, min_p, max_p);
  67. // Check that the leaf size is not too small, given the size of the data
  68. int64_t dx = static_cast<int64_t>((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1;
  69. int64_t dy = static_cast<int64_t>((max_p[1] - min_p[1]) * inverse_leaf_size_[1])+1;
  70. int64_t dz = static_cast<int64_t>((max_p[2] - min_p[2]) * inverse_leaf_size_[2])+1;
  71. if((dx*dy*dz) > std::numeric_limits<int32_t>::max())
  72. {
  73. PCL_WARN("[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.", getClassName().c_str());
  74. output.clear();
  75. return;
  76. }
  77. // Compute the minimum and maximum bounding box values
  78. min_b_[0] = static_cast<int> (floor (min_p[0] * inverse_leaf_size_[0]));
  79. max_b_[0] = static_cast<int> (floor (max_p[0] * inverse_leaf_size_[0]));
  80. min_b_[1] = static_cast<int> (floor (min_p[1] * inverse_leaf_size_[1]));
  81. max_b_[1] = static_cast<int> (floor (max_p[1] * inverse_leaf_size_[1]));
  82. min_b_[2] = static_cast<int> (floor (min_p[2] * inverse_leaf_size_[2]));
  83. max_b_[2] = static_cast<int> (floor (max_p[2] * inverse_leaf_size_[2]));
  84. // Compute the number of divisions needed along all axis
  85. div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones ();
  86. div_b_[3] = 0;
  87. // Clear the leaves
  88. leaves_.clear ();
  89. // leaves_.reserve(8192);
  90. // Set up the division multiplier
  91. divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0);
  92. int centroid_size = 4;
  93. if (downsample_all_data_)
  94. centroid_size = boost::mpl::size<FieldList>::value;
  95. // ---[ RGB special case
  96. std::vector<pcl::PCLPointField> fields;
  97. int rgba_index = -1;
  98. rgba_index = pcl::getFieldIndex (*input_, "rgb", fields);
  99. if (rgba_index == -1)
  100. rgba_index = pcl::getFieldIndex (*input_, "rgba", fields);
  101. if (rgba_index >= 0)
  102. {
  103. rgba_index = fields[rgba_index].offset;
  104. centroid_size += 3;
  105. }
  106. // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first...
  107. if (!filter_field_name_.empty ())
  108. {
  109. // Get the distance field index
  110. std::vector<pcl::PCLPointField> fields;
  111. int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields);
  112. if (distance_idx == -1)
  113. PCL_WARN ("[pcl::%s::applyFilter] Invalid filter field name. Index is %d.\n", getClassName ().c_str (), distance_idx);
  114. // First pass: go over all points and insert them into the right leaf
  115. for (size_t cp = 0; cp < input_->points.size (); ++cp)
  116. {
  117. if (!input_->is_dense)
  118. // Check if the point is invalid
  119. if (!pcl_isfinite (input_->points[cp].x) ||
  120. !pcl_isfinite (input_->points[cp].y) ||
  121. !pcl_isfinite (input_->points[cp].z))
  122. continue;
  123. // Get the distance value
  124. const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&input_->points[cp]);
  125. float distance_value = 0;
  126. memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float));
  127. if (filter_limit_negative_)
  128. {
  129. // Use a threshold for cutting out points which inside the interval
  130. if ((distance_value < filter_limit_max_) && (distance_value > filter_limit_min_))
  131. continue;
  132. }
  133. else
  134. {
  135. // Use a threshold for cutting out points which are too close/far away
  136. if ((distance_value > filter_limit_max_) || (distance_value < filter_limit_min_))
  137. continue;
  138. }
  139. int ijk0 = static_cast<int> (floor (input_->points[cp].x * inverse_leaf_size_[0]) - static_cast<float> (min_b_[0]));
  140. int ijk1 = static_cast<int> (floor (input_->points[cp].y * inverse_leaf_size_[1]) - static_cast<float> (min_b_[1]));
  141. int ijk2 = static_cast<int> (floor (input_->points[cp].z * inverse_leaf_size_[2]) - static_cast<float> (min_b_[2]));
  142. // Compute the centroid leaf index
  143. int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
  144. Leaf& leaf = leaves_[idx];
  145. if (leaf.nr_points == 0)
  146. {
  147. leaf.centroid.resize (centroid_size);
  148. leaf.centroid.setZero ();
  149. }
  150. Eigen::Vector3d pt3d (input_->points[cp].x, input_->points[cp].y, input_->points[cp].z);
  151. // Accumulate point sum for centroid calculation
  152. leaf.mean_ += pt3d;
  153. // Accumulate x*xT for single pass covariance calculation
  154. leaf.cov_ += pt3d * pt3d.transpose ();
  155. // Do we need to process all the fields?
  156. if (!downsample_all_data_)
  157. {
  158. Eigen::Vector4f pt (input_->points[cp].x, input_->points[cp].y, input_->points[cp].z, 0);
  159. leaf.centroid.template head<4> () += pt;
  160. }
  161. else
  162. {
  163. // Copy all the fields
  164. Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size);
  165. // ---[ RGB special case
  166. if (rgba_index >= 0)
  167. {
  168. // fill r/g/b data
  169. int rgb;
  170. memcpy (&rgb, reinterpret_cast<const char*> (&input_->points[cp]) + rgba_index, sizeof (int));
  171. centroid[centroid_size - 3] = static_cast<float> ((rgb >> 16) & 0x0000ff);
  172. centroid[centroid_size - 2] = static_cast<float> ((rgb >> 8) & 0x0000ff);
  173. centroid[centroid_size - 1] = static_cast<float> ((rgb) & 0x0000ff);
  174. }
  175. pcl::for_each_type<FieldList> (pcl::NdCopyPointEigenFunctor<PointT> (input_->points[cp], centroid));
  176. leaf.centroid += centroid;
  177. }
  178. ++leaf.nr_points;
  179. }
  180. }
  181. // No distance filtering, process all data
  182. else
  183. {
  184. // First pass: go over all points and insert them into the right leaf
  185. for (size_t cp = 0; cp < input_->points.size (); ++cp)
  186. {
  187. if (!input_->is_dense)
  188. // Check if the point is invalid
  189. if (!pcl_isfinite (input_->points[cp].x) ||
  190. !pcl_isfinite (input_->points[cp].y) ||
  191. !pcl_isfinite (input_->points[cp].z))
  192. continue;
  193. int ijk0 = static_cast<int> (floor (input_->points[cp].x * inverse_leaf_size_[0]) - static_cast<float> (min_b_[0]));
  194. int ijk1 = static_cast<int> (floor (input_->points[cp].y * inverse_leaf_size_[1]) - static_cast<float> (min_b_[1]));
  195. int ijk2 = static_cast<int> (floor (input_->points[cp].z * inverse_leaf_size_[2]) - static_cast<float> (min_b_[2]));
  196. // Compute the centroid leaf index
  197. int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
  198. //int idx = (((input_->points[cp].getArray4fmap () * inverse_leaf_size_).template cast<int> ()).matrix () - min_b_).dot (divb_mul_);
  199. Leaf& leaf = leaves_[idx];
  200. if (leaf.nr_points == 0)
  201. {
  202. leaf.centroid.resize (centroid_size);
  203. leaf.centroid.setZero ();
  204. }
  205. Eigen::Vector3d pt3d (input_->points[cp].x, input_->points[cp].y, input_->points[cp].z);
  206. // Accumulate point sum for centroid calculation
  207. leaf.mean_ += pt3d;
  208. // Accumulate x*xT for single pass covariance calculation
  209. leaf.cov_ += pt3d * pt3d.transpose ();
  210. // Do we need to process all the fields?
  211. if (!downsample_all_data_)
  212. {
  213. Eigen::Vector4f pt (input_->points[cp].x, input_->points[cp].y, input_->points[cp].z, 0);
  214. leaf.centroid.template head<4> () += pt;
  215. }
  216. else
  217. {
  218. // Copy all the fields
  219. Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size);
  220. // ---[ RGB special case
  221. if (rgba_index >= 0)
  222. {
  223. // Fill r/g/b data, assuming that the order is BGRA
  224. int rgb;
  225. memcpy (&rgb, reinterpret_cast<const char*> (&input_->points[cp]) + rgba_index, sizeof (int));
  226. centroid[centroid_size - 3] = static_cast<float> ((rgb >> 16) & 0x0000ff);
  227. centroid[centroid_size - 2] = static_cast<float> ((rgb >> 8) & 0x0000ff);
  228. centroid[centroid_size - 1] = static_cast<float> ((rgb) & 0x0000ff);
  229. }
  230. pcl::for_each_type<FieldList> (pcl::NdCopyPointEigenFunctor<PointT> (input_->points[cp], centroid));
  231. leaf.centroid += centroid;
  232. }
  233. ++leaf.nr_points;
  234. }
  235. }
  236. // Second pass: go over all leaves and compute centroids and covariance matrices
  237. output.points.reserve (leaves_.size ());
  238. if (searchable_)
  239. voxel_centroids_leaf_indices_.reserve (leaves_.size ());
  240. int cp = 0;
  241. if (save_leaf_layout_)
  242. leaf_layout_.resize (div_b_[0] * div_b_[1] * div_b_[2], -1);
  243. // Eigen values and vectors calculated to prevent near singluar matrices
  244. Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> eigensolver;
  245. Eigen::Matrix3d eigen_val;
  246. Eigen::Vector3d pt_sum;
  247. // Eigen values less than a threshold of max eigen value are inflated to a set fraction of the max eigen value.
  248. double min_covar_eigvalue;
  249. for (auto it = leaves_.begin (); it != leaves_.end (); ++it)
  250. {
  251. // Normalize the centroid
  252. Leaf& leaf = it->second;
  253. // Normalize the centroid
  254. leaf.centroid /= static_cast<float> (leaf.nr_points);
  255. // Point sum used for single pass covariance calculation
  256. pt_sum = leaf.mean_;
  257. // Normalize mean
  258. leaf.mean_ /= leaf.nr_points;
  259. // If the voxel contains sufficient points, its covariance is calculated and is added to the voxel centroids and output clouds.
  260. // Points with less than the minimum points will have a can not be accuratly approximated using a normal distribution.
  261. if (leaf.nr_points >= min_points_per_voxel_)
  262. {
  263. if (save_leaf_layout_)
  264. leaf_layout_[it->first] = cp++;
  265. output.push_back (PointT ());
  266. // Do we need to process all the fields?
  267. if (!downsample_all_data_)
  268. {
  269. output.points.back ().x = leaf.centroid[0];
  270. output.points.back ().y = leaf.centroid[1];
  271. output.points.back ().z = leaf.centroid[2];
  272. }
  273. else
  274. {
  275. pcl::for_each_type<FieldList> (pcl::NdCopyEigenPointFunctor<PointT> (leaf.centroid, output.back ()));
  276. // ---[ RGB special case
  277. if (rgba_index >= 0)
  278. {
  279. // pack r/g/b into rgb
  280. float r = leaf.centroid[centroid_size - 3], g = leaf.centroid[centroid_size - 2], b = leaf.centroid[centroid_size - 1];
  281. int rgb = (static_cast<int> (r)) << 16 | (static_cast<int> (g)) << 8 | (static_cast<int> (b));
  282. memcpy (reinterpret_cast<char*> (&output.points.back ()) + rgba_index, &rgb, sizeof (float));
  283. }
  284. }
  285. // Stores the voxel indice for fast access searching
  286. if (searchable_)
  287. voxel_centroids_leaf_indices_.push_back (static_cast<int> (it->first));
  288. // Single pass covariance calculation
  289. leaf.cov_ = (leaf.cov_ - 2 * (pt_sum * leaf.mean_.transpose ())) / leaf.nr_points + leaf.mean_ * leaf.mean_.transpose ();
  290. leaf.cov_ *= (leaf.nr_points - 1.0) / leaf.nr_points;
  291. //Normalize Eigen Val such that max no more than 100x min.
  292. eigensolver.compute (leaf.cov_);
  293. eigen_val = eigensolver.eigenvalues ().asDiagonal ();
  294. leaf.evecs_ = eigensolver.eigenvectors ();
  295. if (eigen_val (0, 0) < 0 || eigen_val (1, 1) < 0 || eigen_val (2, 2) <= 0)
  296. {
  297. leaf.nr_points = -1;
  298. continue;
  299. }
  300. // Avoids matrices near singularities (eq 6.11)[Magnusson 2009]
  301. min_covar_eigvalue = min_covar_eigvalue_mult_ * eigen_val (2, 2);
  302. if (eigen_val (0, 0) < min_covar_eigvalue)
  303. {
  304. eigen_val (0, 0) = min_covar_eigvalue;
  305. if (eigen_val (1, 1) < min_covar_eigvalue)
  306. {
  307. eigen_val (1, 1) = min_covar_eigvalue;
  308. }
  309. leaf.cov_ = leaf.evecs_ * eigen_val * leaf.evecs_.inverse ();
  310. }
  311. leaf.evals_ = eigen_val.diagonal ();
  312. leaf.icov_ = leaf.cov_.inverse ();
  313. if (leaf.icov_.maxCoeff () == std::numeric_limits<float>::infinity ( )
  314. || leaf.icov_.minCoeff () == -std::numeric_limits<float>::infinity ( ) )
  315. {
  316. leaf.nr_points = -1;
  317. }
  318. }
  319. }
  320. output.width = static_cast<uint32_t> (output.points.size ());
  321. }
  322. //////////////////////////////////////////////////////////////////////////////////////////
  323. template<typename PointT> int
  324. pclomp::VoxelGridCovariance<PointT>::getNeighborhoodAtPoint(const Eigen::MatrixXi& relative_coordinates, const PointT& reference_point, std::vector<LeafConstPtr> &neighbors) const
  325. {
  326. neighbors.clear();
  327. // Find displacement coordinates
  328. Eigen::Vector4i ijk(static_cast<int> (floor(reference_point.x / leaf_size_[0])),
  329. static_cast<int> (floor(reference_point.y / leaf_size_[1])),
  330. static_cast<int> (floor(reference_point.z / leaf_size_[2])), 0);
  331. Eigen::Array4i diff2min = min_b_ - ijk;
  332. Eigen::Array4i diff2max = max_b_ - ijk;
  333. neighbors.reserve(relative_coordinates.cols());
  334. // Check each neighbor to see if it is occupied and contains sufficient points
  335. // Slower than radius search because needs to check 26 indices
  336. for (int ni = 0; ni < relative_coordinates.cols(); ni++)
  337. {
  338. Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished();
  339. // Checking if the specified cell is in the grid
  340. if ((diff2min <= displacement.array()).all() && (diff2max >= displacement.array()).all())
  341. {
  342. auto leaf_iter = leaves_.find(((ijk + displacement - min_b_).dot(divb_mul_)));
  343. if (leaf_iter != leaves_.end() && leaf_iter->second.nr_points >= min_points_per_voxel_)
  344. {
  345. LeafConstPtr leaf = &(leaf_iter->second);
  346. neighbors.push_back(leaf);
  347. }
  348. }
  349. }
  350. return (static_cast<int> (neighbors.size()));
  351. }
  352. //////////////////////////////////////////////////////////////////////////////////////////
  353. template<typename PointT> int
  354. pclomp::VoxelGridCovariance<PointT>::getNeighborhoodAtPoint(const PointT& reference_point, std::vector<LeafConstPtr> &neighbors) const
  355. {
  356. neighbors.clear();
  357. // Find displacement coordinates
  358. Eigen::MatrixXi relative_coordinates = pcl::getAllNeighborCellIndices();
  359. return getNeighborhoodAtPoint(relative_coordinates, reference_point, neighbors);
  360. }
  361. //////////////////////////////////////////////////////////////////////////////////////////
  362. template<typename PointT> int
  363. pclomp::VoxelGridCovariance<PointT>::getNeighborhoodAtPoint7(const PointT& reference_point, std::vector<LeafConstPtr> &neighbors) const
  364. {
  365. neighbors.clear();
  366. Eigen::MatrixXi relative_coordinates(3, 7);
  367. relative_coordinates.setZero();
  368. relative_coordinates(0, 1) = 1;
  369. relative_coordinates(0, 2) = -1;
  370. relative_coordinates(1, 3) = 1;
  371. relative_coordinates(1, 4) = -1;
  372. relative_coordinates(2, 5) = 1;
  373. relative_coordinates(2, 6) = -1;
  374. return getNeighborhoodAtPoint(relative_coordinates, reference_point, neighbors);
  375. }
  376. //////////////////////////////////////////////////////////////////////////////////////////
  377. template<typename PointT> int
  378. pclomp::VoxelGridCovariance<PointT>::getNeighborhoodAtPoint1(const PointT& reference_point, std::vector<LeafConstPtr> &neighbors) const
  379. {
  380. neighbors.clear();
  381. return getNeighborhoodAtPoint(Eigen::MatrixXi::Zero(3,1), reference_point, neighbors);
  382. }
  383. //////////////////////////////////////////////////////////////////////////////////////////
  384. template<typename PointT> void
  385. pclomp::VoxelGridCovariance<PointT>::getDisplayCloud (pcl::PointCloud<pcl::PointXYZ>& cell_cloud)
  386. {
  387. cell_cloud.clear ();
  388. int pnt_per_cell = 1000;
  389. boost::mt19937 rng;
  390. boost::normal_distribution<> nd (0.0, leaf_size_.head (3).norm ());
  391. boost::variate_generator<boost::mt19937&, boost::normal_distribution<> > var_nor (rng, nd);
  392. Eigen::LLT<Eigen::Matrix3d> llt_of_cov;
  393. Eigen::Matrix3d cholesky_decomp;
  394. Eigen::Vector3d cell_mean;
  395. Eigen::Vector3d rand_point;
  396. Eigen::Vector3d dist_point;
  397. // Generate points for each occupied voxel with sufficient points.
  398. for (auto it = leaves_.begin (); it != leaves_.end (); ++it)
  399. {
  400. Leaf& leaf = it->second;
  401. if (leaf.nr_points >= min_points_per_voxel_)
  402. {
  403. cell_mean = leaf.mean_;
  404. llt_of_cov.compute (leaf.cov_);
  405. cholesky_decomp = llt_of_cov.matrixL ();
  406. // Random points generated by sampling the normal distribution given by voxel mean and covariance matrix
  407. for (int i = 0; i < pnt_per_cell; i++)
  408. {
  409. rand_point = Eigen::Vector3d (var_nor (), var_nor (), var_nor ());
  410. dist_point = cell_mean + cholesky_decomp * rand_point;
  411. cell_cloud.push_back (pcl::PointXYZ (static_cast<float> (dist_point (0)), static_cast<float> (dist_point (1)), static_cast<float> (dist_point (2))));
  412. }
  413. }
  414. }
  415. }
  416. #define PCL_INSTANTIATE_VoxelGridCovariance(T) template class PCL_EXPORTS pcl::VoxelGridCovariance<T>;
  417. #endif // PCL_VOXEL_GRID_COVARIANCE_IMPL_H_