VoxelGrid.cpp 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791
  1. #include "ndt_cpu/VoxelGrid.h"
  2. #include "ndt_cpu/debug.h"
  3. #include <math.h>
  4. #include <limits>
  5. #include <inttypes.h>
  6. #include <vector>
  7. #include <cmath>
  8. #include <stdio.h>
  9. #include <sys/time.h>
  10. #include "ndt_cpu/SymmetricEigenSolver.h"
  11. namespace cpu {
  12. template <typename PointSourceType>
  13. VoxelGrid<PointSourceType>::VoxelGrid():
  14. voxel_num_(0),
  15. max_x_(FLT_MIN),
  16. max_y_(FLT_MIN),
  17. max_z_(FLT_MIN),
  18. min_x_(FLT_MAX),
  19. min_y_(FLT_MAX),
  20. min_z_(FLT_MAX),
  21. voxel_x_(0),
  22. voxel_y_(0),
  23. voxel_z_(0),
  24. max_b_x_(0),
  25. max_b_y_(0),
  26. max_b_z_(0),
  27. min_b_x_(0),
  28. min_b_y_(0),
  29. min_b_z_(0),
  30. vgrid_x_(0),
  31. vgrid_y_(0),
  32. vgrid_z_(0),
  33. min_points_per_voxel_(6),
  34. real_max_bx_(INT_MIN),
  35. real_max_by_(INT_MIN),
  36. real_max_bz_(INT_MIN),
  37. real_min_bx_(INT_MAX),
  38. real_min_by_(INT_MAX),
  39. real_min_bz_(INT_MAX)
  40. {
  41. centroid_.reset();
  42. icovariance_.reset();
  43. points_id_.reset();
  44. points_per_voxel_.reset();
  45. tmp_centroid_.reset();
  46. tmp_cov_.reset();
  47. };
  48. template <typename PointSourceType>
  49. int VoxelGrid<PointSourceType>::roundUp(int input, int factor)
  50. {
  51. return (input < 0) ? -((-input) / factor) * factor : ((input + factor - 1) / factor) * factor;
  52. }
  53. template <typename PointSourceType>
  54. int VoxelGrid<PointSourceType>::roundDown(int input, int factor)
  55. {
  56. return (input < 0) ? -((-input + factor - 1) / factor) * factor : (input / factor) * factor;
  57. }
  58. template <typename PointSourceType>
  59. int VoxelGrid<PointSourceType>::div(int input, int divisor)
  60. {
  61. return (input < 0) ? -((-input + divisor - 1) / divisor) : input / divisor;
  62. }
  63. template <typename PointSourceType>
  64. void VoxelGrid<PointSourceType>::initialize()
  65. {
  66. centroid_.reset();
  67. centroid_ = boost::make_shared<std::vector<Eigen::Vector3d> >(voxel_num_);
  68. icovariance_.reset();
  69. icovariance_ = boost::make_shared<std::vector<Eigen::Matrix3d> >(voxel_num_);
  70. points_id_.reset();
  71. points_id_ = boost::make_shared<std::vector<std::vector<int> > >(voxel_num_);
  72. points_per_voxel_.reset();
  73. points_per_voxel_ = boost::make_shared<std::vector<int> >(voxel_num_, 0);
  74. tmp_centroid_.reset();
  75. tmp_centroid_ = boost::make_shared<std::vector<Eigen::Vector3d> >(voxel_num_);
  76. tmp_cov_.reset();
  77. tmp_cov_ = boost::make_shared<std::vector<Eigen::Matrix3d> >(voxel_num_);
  78. }
  79. template <typename PointSourceType>
  80. int VoxelGrid<PointSourceType>::getVoxelNum() const
  81. {
  82. return voxel_num_;
  83. }
  84. template <typename PointSourceType>
  85. float VoxelGrid<PointSourceType>::getMaxX() const
  86. {
  87. return max_x_;
  88. }
  89. template <typename PointSourceType>
  90. float VoxelGrid<PointSourceType>::getMaxY() const
  91. {
  92. return max_y_;
  93. }
  94. template <typename PointSourceType>
  95. float VoxelGrid<PointSourceType>::getMaxZ() const
  96. {
  97. return max_z_;
  98. }
  99. template <typename PointSourceType>
  100. float VoxelGrid<PointSourceType>::getMinX() const
  101. {
  102. return min_x_;
  103. }
  104. template <typename PointSourceType>
  105. float VoxelGrid<PointSourceType>::getMinY() const
  106. {
  107. return min_y_;
  108. }
  109. template <typename PointSourceType>
  110. float VoxelGrid<PointSourceType>::getMinZ() const
  111. {
  112. return min_z_;
  113. }
  114. template <typename PointSourceType>
  115. float VoxelGrid<PointSourceType>::getVoxelX() const
  116. {
  117. return voxel_x_;
  118. }
  119. template <typename PointSourceType>
  120. float VoxelGrid<PointSourceType>::getVoxelY() const
  121. {
  122. return voxel_y_;
  123. }
  124. template <typename PointSourceType>
  125. float VoxelGrid<PointSourceType>::getVoxelZ() const
  126. {
  127. return voxel_z_;
  128. }
  129. template <typename PointSourceType>
  130. int VoxelGrid<PointSourceType>::getMaxBX() const
  131. {
  132. return max_b_x_;
  133. }
  134. template <typename PointSourceType>
  135. int VoxelGrid<PointSourceType>::getMaxBY() const
  136. {
  137. return max_b_y_;
  138. }
  139. template <typename PointSourceType>
  140. int VoxelGrid<PointSourceType>::getMaxBZ() const
  141. {
  142. return max_b_z_;
  143. }
  144. template <typename PointSourceType>
  145. int VoxelGrid<PointSourceType>::getMinBX() const
  146. {
  147. return min_b_x_;
  148. }
  149. template <typename PointSourceType>
  150. int VoxelGrid<PointSourceType>::getMinBY() const
  151. {
  152. return min_b_y_;
  153. }
  154. template <typename PointSourceType>
  155. int VoxelGrid<PointSourceType>::getMinBZ() const
  156. {
  157. return min_b_z_;
  158. }
  159. template <typename PointSourceType>
  160. int VoxelGrid<PointSourceType>::getVgridX() const
  161. {
  162. return vgrid_x_;
  163. }
  164. template <typename PointSourceType>
  165. int VoxelGrid<PointSourceType>::getVgridY() const
  166. {
  167. return vgrid_y_;
  168. }
  169. template <typename PointSourceType>
  170. int VoxelGrid<PointSourceType>::getVgridZ() const
  171. {
  172. return vgrid_z_;
  173. }
  174. template <typename PointSourceType>
  175. Eigen::Vector3d VoxelGrid<PointSourceType>::getCentroid(int voxel_id) const
  176. {
  177. return (*centroid_)[voxel_id];
  178. }
  179. template <typename PointSourceType>
  180. Eigen::Matrix3d VoxelGrid<PointSourceType>::getInverseCovariance(int voxel_id) const
  181. {
  182. return (*icovariance_)[voxel_id];
  183. }
  184. template <typename PointSourceType>
  185. void VoxelGrid<PointSourceType>::setLeafSize(float voxel_x, float voxel_y, float voxel_z)
  186. {
  187. voxel_x_ = voxel_x;
  188. voxel_y_ = voxel_y;
  189. voxel_z_ = voxel_z;
  190. }
  191. template <typename PointSourceType>
  192. int VoxelGrid<PointSourceType>::voxelId(PointSourceType p)
  193. {
  194. int idx = static_cast<int>(floor(p.x / voxel_x_)) - min_b_x_;
  195. int idy = static_cast<int>(floor(p.y / voxel_y_)) - min_b_y_;
  196. int idz = static_cast<int>(floor(p.z / voxel_z_)) - min_b_z_;
  197. return (idx + idy * vgrid_x_ + idz * vgrid_x_ * vgrid_y_);
  198. }
  199. template <typename PointSourceType>
  200. int VoxelGrid<PointSourceType>::voxelId(PointSourceType p,
  201. float voxel_x, float voxel_y, float voxel_z,
  202. int min_b_x, int min_b_y, int min_b_z,
  203. int vgrid_x, int vgrid_y, int vgrid_z)
  204. {
  205. int idx = static_cast<int>(floor(p.x / voxel_x)) - min_b_x;
  206. int idy = static_cast<int>(floor(p.y / voxel_y)) - min_b_y;
  207. int idz = static_cast<int>(floor(p.z / voxel_z)) - min_b_z;
  208. return (idx + idy * vgrid_x + idz * vgrid_x * vgrid_y);
  209. }
  210. template <typename PointSourceType>
  211. int VoxelGrid<PointSourceType>::voxelId(int idx, int idy, int idz,
  212. int min_b_x, int min_b_y, int min_b_z,
  213. int size_x, int size_y, int size_z)
  214. {
  215. return (idx - min_b_x) + (idy - min_b_y) * size_x + (idz - min_b_z) * size_x * size_y;
  216. }
  217. template <typename PointSourceType>
  218. void VoxelGrid<PointSourceType>::computeCentroidAndCovariance()
  219. {
  220. for (int idx = real_min_bx_; idx <= real_max_bx_; idx++)
  221. for (int idy = real_min_by_; idy <= real_max_by_; idy++)
  222. for (int idz = real_min_bz_; idz <= real_max_bz_; idz++) {
  223. int i = voxelId(idx, idy, idz, min_b_x_, min_b_y_, min_b_z_, vgrid_x_, vgrid_y_, vgrid_z_);
  224. int ipoint_num = (*points_id_)[i].size();
  225. double point_num = static_cast<double>(ipoint_num);
  226. Eigen::Vector3d pt_sum = (*tmp_centroid_)[i];
  227. if (ipoint_num > 0) {
  228. (*centroid_)[i] = pt_sum / point_num;
  229. }
  230. Eigen::Matrix3d covariance;
  231. if (ipoint_num >= min_points_per_voxel_) {
  232. covariance = ((*tmp_cov_)[i] - 2.0 * (pt_sum * (*centroid_)[i].transpose())) / point_num + (*centroid_)[i] * (*centroid_)[i].transpose();
  233. covariance *= (point_num - 1.0) / point_num;
  234. SymmetricEigensolver3x3 sv(covariance);
  235. sv.compute();
  236. Eigen::Matrix3d evecs = sv.eigenvectors();
  237. Eigen::Matrix3d evals = sv.eigenvalues().asDiagonal();
  238. if (evals(0, 0) < 0 || evals(1, 1) < 0 || evals(2, 2) <= 0) {
  239. (*points_per_voxel_)[i] = -1;
  240. continue;
  241. }
  242. double min_cov_eigvalue = evals(2, 2) * 0.01;
  243. if (evals(0, 0) < min_cov_eigvalue) {
  244. evals(0, 0) = min_cov_eigvalue;
  245. if (evals(1, 1) < min_cov_eigvalue) {
  246. evals(1, 1) = min_cov_eigvalue;
  247. }
  248. covariance = evecs * evals * evecs.inverse();
  249. }
  250. (*icovariance_)[i] = covariance.inverse();
  251. }
  252. }
  253. }
  254. //Input are supposed to be in device memory
  255. template <typename PointSourceType>
  256. void VoxelGrid<PointSourceType>::setInput(typename pcl::PointCloud<PointSourceType>::Ptr input_cloud)
  257. {
  258. if (input_cloud->points.size() > 0) {
  259. /* If no voxel grid was created, then
  260. * build the initial voxel grid and octree
  261. */
  262. source_cloud_ = input_cloud;
  263. findBoundaries();
  264. std::vector<Eigen::Vector3i> voxel_ids(input_cloud->points.size());
  265. for (int i = 0; i < input_cloud->points.size(); i++) {
  266. Eigen::Vector3i &vid = voxel_ids[i];
  267. PointSourceType p = input_cloud->points[i];
  268. vid(0) = static_cast<int>(floor(p.x / voxel_x_));
  269. vid(1) = static_cast<int>(floor(p.y / voxel_y_));
  270. vid(2) = static_cast<int>(floor(p.z / voxel_z_));
  271. }
  272. octree_.setInput(voxel_ids, input_cloud);
  273. voxel_ids.clear();
  274. initialize();
  275. scatterPointsToVoxelGrid();
  276. computeCentroidAndCovariance();
  277. }
  278. }
  279. template <typename PointSourceType>
  280. void VoxelGrid<PointSourceType>::findBoundaries()
  281. {
  282. findBoundaries(source_cloud_, max_x_, max_y_, max_z_, min_x_, min_y_, min_z_);
  283. real_max_bx_ = max_b_x_ = static_cast<int> (floor(max_x_ / voxel_x_));
  284. real_max_by_ = max_b_y_ = static_cast<int> (floor(max_y_ / voxel_y_));
  285. real_max_bz_ = max_b_z_ = static_cast<int> (floor(max_z_ / voxel_z_));
  286. real_min_bx_ = min_b_x_ = static_cast<int> (floor(min_x_ / voxel_x_));
  287. real_min_by_ = min_b_y_ = static_cast<int> (floor(min_y_ / voxel_y_));
  288. real_min_bz_ = min_b_z_ = static_cast<int> (floor(min_z_ / voxel_z_));
  289. /* Allocate a poll of memory that is larger than the requested memory so
  290. * we do not have to reallocate buffers when the target cloud is set
  291. */
  292. /* Max bounds round toward plus infinity */
  293. max_b_x_ = roundUp(max_b_x_, MAX_BX_);
  294. max_b_y_ = roundUp(max_b_y_, MAX_BY_);
  295. max_b_z_ = roundUp(max_b_z_, MAX_BZ_);
  296. /* Min bounds round toward minus infinity */
  297. min_b_x_ = roundDown(min_b_x_, MAX_BX_);
  298. min_b_y_ = roundDown(min_b_y_, MAX_BY_);
  299. min_b_z_ = roundDown(min_b_z_, MAX_BZ_);
  300. vgrid_x_ = max_b_x_ - min_b_x_ + 1;
  301. vgrid_y_ = max_b_y_ - min_b_y_ + 1;
  302. vgrid_z_ = max_b_z_ - min_b_z_ + 1;
  303. if (vgrid_x_ > 0 && vgrid_y_ > 0 && vgrid_z_ > 0) {
  304. voxel_num_ = vgrid_x_ * vgrid_y_ * vgrid_z_;
  305. } else {
  306. voxel_num_ = 0;
  307. }
  308. }
  309. template <typename PointSourceType>
  310. void VoxelGrid<PointSourceType>::findBoundaries(typename pcl::PointCloud<PointSourceType>::Ptr input_cloud,
  311. float &max_x, float &max_y, float &max_z,
  312. float &min_x, float &min_y, float &min_z)
  313. {
  314. max_x = max_y = max_z = -FLT_MAX;
  315. min_x = min_y = min_z = FLT_MAX;
  316. for (int i = 0; i < input_cloud->points.size(); i++) {
  317. float x = input_cloud->points[i].x;
  318. float y = input_cloud->points[i].y;
  319. float z = input_cloud->points[i].z;
  320. max_x = (max_x > x) ? max_x : x;
  321. max_y = (max_y > y) ? max_y : y;
  322. max_z = (max_z > z) ? max_z : z;
  323. min_x = (min_x < x) ? min_x : x;
  324. min_y = (min_y < y) ? min_y : y;
  325. min_z = (min_z < z) ? min_z : z;
  326. }
  327. }
  328. template <typename PointSourceType>
  329. void VoxelGrid<PointSourceType>::radiusSearch(PointSourceType p, float radius, std::vector<int> &voxel_ids, int max_nn)
  330. {
  331. float t_x = p.x;
  332. float t_y = p.y;
  333. float t_z = p.z;
  334. int max_id_x = static_cast<int>(floor((t_x + radius) / voxel_x_));
  335. int max_id_y = static_cast<int>(floor((t_y + radius) / voxel_y_));
  336. int max_id_z = static_cast<int>(floor((t_z + radius) / voxel_z_));
  337. int min_id_x = static_cast<int>(floor((t_x - radius) / voxel_x_));
  338. int min_id_y = static_cast<int>(floor((t_y - radius) / voxel_y_));
  339. int min_id_z = static_cast<int>(floor((t_z - radius) / voxel_z_));
  340. /* Find intersection of the cube containing
  341. * the NN sphere of the point and the voxel grid
  342. */
  343. max_id_x = (max_id_x > real_max_bx_) ? real_max_bx_ : max_id_x;
  344. max_id_y = (max_id_y > real_max_by_) ? real_max_by_ : max_id_y;
  345. max_id_z = (max_id_z > real_max_bz_) ? real_max_bz_ : max_id_z;
  346. min_id_x = (min_id_x < real_min_bx_) ? real_min_bx_ : min_id_x;
  347. min_id_y = (min_id_y < real_min_by_) ? real_min_by_ : min_id_y;
  348. min_id_z = (min_id_z < real_min_bz_) ? real_min_bz_ : min_id_z;
  349. int nn = 0;
  350. for (int idx = min_id_x; idx <= max_id_x && nn < max_nn; idx++) {
  351. for (int idy = min_id_y; idy <= max_id_y && nn < max_nn; idy++) {
  352. for (int idz = min_id_z; idz <= max_id_z && nn < max_nn; idz++) {
  353. int vid = voxelId(idx, idy, idz,
  354. min_b_x_, min_b_y_, min_b_z_,
  355. vgrid_x_, vgrid_y_, vgrid_z_);
  356. if ((*points_per_voxel_)[vid] >= min_points_per_voxel_) {
  357. double cx = (*centroid_)[vid](0) - static_cast<double>(t_x);
  358. double cy = (*centroid_)[vid](1) - static_cast<double>(t_y);
  359. double cz = (*centroid_)[vid](2) - static_cast<double>(t_z);
  360. double distance = sqrt(cx * cx + cy * cy + cz * cz);
  361. if (distance < radius) {
  362. nn++;
  363. voxel_ids.push_back(vid);
  364. }
  365. }
  366. }
  367. }
  368. }
  369. }
  370. template <typename PointSourceType>
  371. void VoxelGrid<PointSourceType>::scatterPointsToVoxelGrid()
  372. {
  373. for (int pid = 0; pid < source_cloud_->points.size(); pid++) {
  374. int vid = voxelId(source_cloud_->points[pid]);
  375. PointSourceType p = source_cloud_->points[pid];
  376. Eigen::Vector3d p3d(p.x, p.y, p.z);
  377. if ((*points_id_)[vid].size() == 0) {
  378. (*centroid_)[vid].setZero();
  379. (*points_per_voxel_)[vid] = 0;
  380. (*tmp_centroid_)[vid].setZero();
  381. (*tmp_cov_)[vid].setIdentity();
  382. }
  383. (*tmp_centroid_)[vid] += p3d;
  384. (*tmp_cov_)[vid] += p3d * p3d.transpose();
  385. (*points_id_)[vid].push_back(pid);
  386. (*points_per_voxel_)[vid]++;
  387. }
  388. }
  389. template <typename PointSourceType>
  390. int VoxelGrid<PointSourceType>::nearestVoxel(PointSourceType query_point, Eigen::Matrix<float, 6, 1> boundaries, float max_range)
  391. {
  392. // Index of the origin of the circle (query point)
  393. float qx = query_point.x;
  394. float qy = query_point.y;
  395. float qz = query_point.z;
  396. int lower_x = static_cast<int>(floor(boundaries(0) / voxel_x_));
  397. int lower_y = static_cast<int>(floor(boundaries(1) / voxel_y_));
  398. int lower_z = static_cast<int>(floor(boundaries(2) / voxel_z_));
  399. int upper_x = static_cast<int>(floor(boundaries(3) / voxel_x_));
  400. int upper_y = static_cast<int>(floor(boundaries(4) / voxel_y_));
  401. int upper_z = static_cast<int>(floor(boundaries(5) / voxel_z_));
  402. double min_dist = DBL_MAX;
  403. int nn_vid = -1;
  404. for (int i = lower_x; i <= upper_x; i++) {
  405. for (int j = lower_y; j <= upper_y; j++) {
  406. for (int k = lower_z; k <= upper_z; k++) {
  407. int vid = voxelId(i, j, k, min_b_x_, min_b_y_, min_b_z_, vgrid_x_, vgrid_y_, vgrid_z_);
  408. Eigen::Vector3d c = (*centroid_)[vid];
  409. if ((*points_id_)[vid].size() > 0) {
  410. double cur_dist = sqrt((qx - c(0)) * (qx - c(0)) + (qy - c(1)) * (qy - c(1)) + (qz - c(2)) * (qz - c(2)));
  411. if (cur_dist < min_dist) {
  412. min_dist = cur_dist;
  413. nn_vid = vid;
  414. }
  415. }
  416. }
  417. }
  418. }
  419. return nn_vid;
  420. }
  421. template <typename PointSourceType>
  422. double VoxelGrid<PointSourceType>::nearestNeighborDistance(PointSourceType q, float max_range)
  423. {
  424. Eigen::Matrix<float, 6, 1> nn_node_bounds;
  425. nn_node_bounds = octree_.nearestOctreeNode(q);
  426. int nn_vid = nearestVoxel(q, nn_node_bounds, max_range);
  427. Eigen::Vector3d c = (*centroid_)[nn_vid];
  428. double min_dist = sqrt((q.x - c(0)) * (q.x - c(0)) + (q.y - c(1)) * (q.y - c(1)) + (q.z - c(2)) * (q.z - c(2)));
  429. if (min_dist >= max_range) {
  430. return DBL_MAX;
  431. }
  432. return min_dist;
  433. }
  434. template <typename PointSourceType>
  435. void VoxelGrid<PointSourceType>::updateBoundaries(float max_x, float max_y, float max_z,
  436. float min_x, float min_y, float min_z)
  437. {
  438. float new_max_x, new_max_y, new_max_z;
  439. float new_min_x, new_min_y, new_min_z;
  440. new_max_x = (max_x_ >= max_x) ? max_x_ : max_x;
  441. new_max_y = (max_y_ >= max_y) ? max_y_ : max_y;
  442. new_max_z = (max_z_ >= max_z) ? max_z_ : max_z;
  443. new_min_x = (min_x_ <= min_x) ? min_x_ : min_x;
  444. new_min_y = (min_y_ <= min_y) ? min_y_ : min_y;
  445. new_min_z = (min_z_ <= min_z) ? min_z_ : min_z;
  446. /* If the boundaries change, then we need to extend the list of voxels */
  447. if (new_max_x > max_x_ || new_max_y > max_y_ || new_max_z > max_z_ ||
  448. new_min_x < min_x_ || new_min_y < min_y_ || new_min_z < min_z_) {
  449. int max_b_x = static_cast<int> (floor(new_max_x / voxel_x_));
  450. int max_b_y = static_cast<int> (floor(new_max_y / voxel_y_));
  451. int max_b_z = static_cast<int> (floor(new_max_z / voxel_z_));
  452. int min_b_x = static_cast<int> (floor(new_min_x / voxel_x_));
  453. int min_b_y = static_cast<int> (floor(new_min_y / voxel_y_));
  454. int min_b_z = static_cast<int> (floor(new_min_z / voxel_z_));
  455. int real_max_bx = max_b_x;
  456. int real_max_by = max_b_y;
  457. int real_max_bz = max_b_z;
  458. int real_min_bx = min_b_x;
  459. int real_min_by = min_b_y;
  460. int real_min_bz = min_b_z;
  461. /* Max bounds round toward plus infinity */
  462. max_b_x = roundUp(max_b_x, MAX_BX_);
  463. max_b_y = roundUp(max_b_y, MAX_BY_);
  464. max_b_z = roundUp(max_b_z, MAX_BZ_);
  465. /* Min bounds round toward minus infinity */
  466. min_b_x = roundDown(min_b_x, MAX_BX_);
  467. min_b_y = roundDown(min_b_y, MAX_BY_);
  468. min_b_z = roundDown(min_b_z, MAX_BZ_);
  469. if (max_b_x > max_b_x_ || max_b_y > max_b_y_ || max_b_z > max_b_z_ ||
  470. min_b_x < min_b_x_ || min_b_y < min_b_y_ || min_b_z < min_b_z_) {
  471. int vgrid_x = max_b_x - min_b_x + 1;
  472. int vgrid_y = max_b_y - min_b_y + 1;
  473. int vgrid_z = max_b_z - min_b_z + 1;
  474. int voxel_num = vgrid_x * vgrid_y * vgrid_z;
  475. boost::shared_ptr<std::vector<Eigen::Vector3d> > old_centroid = centroid_;
  476. boost::shared_ptr<std::vector<Eigen::Matrix3d> > old_icovariance = icovariance_;
  477. boost::shared_ptr<std::vector<std::vector<int> > > old_points_id = points_id_;
  478. boost::shared_ptr<std::vector<int> > old_points_per_voxel = points_per_voxel_;
  479. boost::shared_ptr<std::vector<Eigen::Vector3d> > old_tmp_centroid = tmp_centroid_;
  480. boost::shared_ptr<std::vector<Eigen::Matrix3d> > old_tmp_cov = tmp_cov_;
  481. centroid_ = boost::make_shared<std::vector<Eigen::Vector3d> >(voxel_num);
  482. icovariance_ = boost::make_shared<std::vector<Eigen::Matrix3d> >(voxel_num);
  483. points_id_ = boost::make_shared<std::vector<std::vector<int> > >(voxel_num);
  484. points_per_voxel_ = boost::make_shared<std::vector<int> >(voxel_num, 0);
  485. tmp_centroid_ = boost::make_shared<std::vector<Eigen::Vector3d> >(voxel_num);
  486. tmp_cov_ = boost::make_shared<std::vector<Eigen::Matrix3d> >(voxel_num);
  487. // Move the old non-empty voxels to the new list of voxels
  488. int idx, idy, idz;
  489. int old_id, new_id;
  490. for (int idx = real_min_bx_; idx <= real_max_bx_; idx++) {
  491. for (int idy = real_min_by_; idy <= real_max_by_; idy++) {
  492. for (int idz = real_min_bz_; idz <= real_max_bz_; idz++) {
  493. old_id = voxelId(idx, idy, idz,
  494. min_b_x_, min_b_y_, min_b_z_,
  495. vgrid_x_, vgrid_y_, vgrid_z_);
  496. new_id = voxelId(idx, idy, idz,
  497. min_b_x, min_b_y, min_b_z,
  498. vgrid_x, vgrid_y, vgrid_z);
  499. if ((*old_points_id)[old_id].size() > 0) {
  500. (*points_per_voxel_)[new_id] = (*old_points_per_voxel)[old_id];
  501. (*centroid_)[new_id] = (*old_centroid)[old_id];
  502. (*icovariance_)[new_id] = (*old_icovariance)[old_id];
  503. (*points_id_)[new_id] = (*old_points_id)[old_id];
  504. (*tmp_centroid_)[new_id] = (*old_tmp_centroid)[old_id];
  505. (*tmp_cov_)[new_id] = (*old_tmp_cov)[old_id];
  506. }
  507. }
  508. }
  509. }
  510. // Update boundaries of voxels
  511. max_b_x_ = max_b_x;
  512. max_b_y_ = max_b_y;
  513. max_b_z_ = max_b_z;
  514. min_b_x_ = min_b_x;
  515. min_b_y_ = min_b_y;
  516. min_b_z_ = min_b_z;
  517. vgrid_x_ = vgrid_x;
  518. vgrid_y_ = vgrid_y;
  519. vgrid_z_ = vgrid_z;
  520. voxel_num_ = voxel_num;
  521. }
  522. // Update actual voxel boundaries
  523. real_min_bx_ = real_min_bx;
  524. real_min_by_ = real_min_by;
  525. real_min_bz_ = real_min_bz;
  526. real_max_bx_ = real_max_bx;
  527. real_max_by_ = real_max_by;
  528. real_max_bz_ = real_max_bz;
  529. //Update boundaries of points
  530. max_x_ = new_max_x;
  531. max_y_ = new_max_y;
  532. max_z_ = new_max_z;
  533. min_x_ = new_min_x;
  534. min_y_ = new_min_y;
  535. min_z_ = new_min_z;
  536. }
  537. }
  538. template <typename PointSourceType>
  539. void VoxelGrid<PointSourceType>::update(typename pcl::PointCloud<PointSourceType>::Ptr new_cloud)
  540. {
  541. if (new_cloud->points.size() <= 0) {
  542. return;
  543. }
  544. float new_max_x, new_max_y, new_max_z;
  545. float new_min_x, new_min_y, new_min_z;
  546. // Find boundaries of the new point cloud
  547. findBoundaries(new_cloud, new_max_x, new_max_y, new_max_z, new_min_x, new_min_y, new_min_z);
  548. /* Update current boundaries of the voxel grid
  549. * Also allocate buffer for new voxel grid and
  550. * octree and move the current voxel grid and
  551. * octree to the new buffer if necessary
  552. */
  553. updateBoundaries(new_max_x, new_max_y, new_max_z, new_min_x, new_min_y, new_min_z);
  554. /* Update changed voxels (voxels that contains new points).
  555. * Update centroids of voxels and their covariance matrixes
  556. * as well as inverse covariance matrixes */
  557. updateVoxelContent(new_cloud);
  558. /* Update octree */
  559. std::vector<Eigen::Vector3i> new_voxel_id(new_cloud->points.size());
  560. for (int i = 0; i < new_cloud->points.size(); i++) {
  561. Eigen::Vector3i &vid = new_voxel_id[i];
  562. PointSourceType p = new_cloud->points[i];
  563. vid(0) = static_cast<int>(floor(p.x / voxel_x_));
  564. vid(1) = static_cast<int>(floor(p.y / voxel_y_));
  565. vid(2) = static_cast<int>(floor(p.z / voxel_z_));
  566. }
  567. octree_.update(new_voxel_id, new_cloud);
  568. *source_cloud_ += *new_cloud;
  569. }
  570. template <typename PointSourceType>
  571. void VoxelGrid<PointSourceType>::updateVoxelContent(typename pcl::PointCloud<PointSourceType>::Ptr new_cloud)
  572. {
  573. int total_points_num = source_cloud_->points.size();
  574. for (int i = 0; i < new_cloud->points.size(); i++) {
  575. PointSourceType p = new_cloud->points[i];
  576. Eigen::Vector3d p3d(p.x, p.y, p.z);
  577. int vx = static_cast<int>(floor(p.x / voxel_x_));
  578. int vy = static_cast<int>(floor(p.y / voxel_y_));
  579. int vz = static_cast<int>(floor(p.z / voxel_z_));
  580. int vid = voxelId(vx, vy, vz, min_b_x_, min_b_y_, min_b_z_, vgrid_x_, vgrid_y_, vgrid_z_);
  581. std::vector<int> &tmp_pid = (*points_id_)[vid];
  582. if (tmp_pid.size() == 0) {
  583. (*centroid_)[vid].setZero();
  584. (*tmp_cov_)[vid].setIdentity();
  585. (*tmp_centroid_)[vid].setZero();
  586. }
  587. (*tmp_centroid_)[vid] += p3d;
  588. (*tmp_cov_)[vid] += p3d * p3d.transpose();
  589. (*points_id_)[vid].push_back(total_points_num + i);
  590. // Update centroids
  591. int ipoint_num = (*points_id_)[vid].size();
  592. (*centroid_)[vid] = (*tmp_centroid_)[vid] / static_cast<double>(ipoint_num);
  593. (*points_per_voxel_)[vid] = ipoint_num;
  594. // Update covariance
  595. double point_num = static_cast<double>(ipoint_num);
  596. Eigen::Vector3d pt_sum = (*tmp_centroid_)[vid];
  597. // Update centroids
  598. (*centroid_)[vid] = (*tmp_centroid_)[vid] / point_num;
  599. if (ipoint_num >= min_points_per_voxel_) {
  600. Eigen::Matrix3d covariance;
  601. covariance = ((*tmp_cov_)[vid] - 2.0 * (pt_sum * (*centroid_)[vid].transpose())) / point_num + (*centroid_)[vid] * (*centroid_)[vid].transpose();
  602. covariance *= (point_num - 1.0) / point_num;
  603. SymmetricEigensolver3x3 sv(covariance);
  604. sv.compute();
  605. Eigen::Matrix3d evecs = sv.eigenvectors();
  606. Eigen::Matrix3d evals = sv.eigenvalues().asDiagonal();
  607. if (evals(0, 0) < 0 || evals(1, 1) < 0 || evals(2, 2) <= 0) {
  608. (*points_per_voxel_)[vid] = -1;
  609. continue;
  610. }
  611. double min_cov_eigvalue = evals(2, 2) * 0.01;
  612. if (evals(0, 0) < min_cov_eigvalue) {
  613. evals(0, 0) = min_cov_eigvalue;
  614. if (evals(1, 1) < min_cov_eigvalue) {
  615. evals(1, 1) = min_cov_eigvalue;
  616. }
  617. covariance = evecs * evals * evecs.inverse();
  618. }
  619. (*icovariance_)[vid] = covariance.inverse();
  620. }
  621. }
  622. }
  623. template class VoxelGrid<pcl::PointXYZI>;
  624. template class VoxelGrid<pcl::PointXYZ>;
  625. }