voxel_generator.cpp 7.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224
  1. // Copyright 2021 TIER IV, Inc.
  2. //
  3. // Licensed under the Apache License, Version 2.0 (the "License");
  4. // you may not use this file except in compliance with the License.
  5. // You may obtain a copy of the License at
  6. //
  7. // http://www.apache.org/licenses/LICENSE-2.0
  8. //
  9. // Unless required by applicable law or agreed to in writing, software
  10. // distributed under the License is distributed on an "AS IS" BASIS,
  11. // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  12. // See the License for the specific language governing permissions and
  13. // limitations under the License.
  14. #include "lidar_centerpoint/preprocess/voxel_generator.hpp"
  15. //#include <sensor_msgs/point_cloud2_iterator.hpp>
  16. #include <memory>
  17. #include <Eigen/Eigen>
  18. namespace centerpoint
  19. {
  20. VoxelGeneratorTemplate::VoxelGeneratorTemplate(
  21. const DensificationParam & param, const CenterPointConfig & config)
  22. : config_(config)
  23. {
  24. pd_ptr_ = std::make_unique<PointCloudDensification>(param);
  25. range_[0] = config.range_min_x_;
  26. range_[1] = config.range_min_y_;
  27. range_[2] = config.range_min_z_;
  28. range_[3] = config.range_max_x_;
  29. range_[4] = config.range_max_y_;
  30. range_[5] = config.range_max_z_;
  31. grid_size_[0] = config.grid_size_x_;
  32. grid_size_[1] = config.grid_size_y_;
  33. grid_size_[2] = config.grid_size_z_;
  34. recip_voxel_size_[0] = 1 / config.voxel_size_x_;
  35. recip_voxel_size_[1] = 1 / config.voxel_size_y_;
  36. recip_voxel_size_[2] = 1 / config.voxel_size_z_;
  37. }
  38. bool VoxelGeneratorTemplate::enqueuePointCloud(
  39. const pcl::PointCloud<pcl::PointXYZI>::Ptr pc_ptr)
  40. {
  41. return pd_ptr_->enqueuePointCloud(pc_ptr);
  42. }
  43. //bool VoxelGeneratorTemplate::enqueuePointCloud(
  44. // const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer)
  45. //{
  46. // return pd_ptr_->enqueuePointCloud(input_pointcloud_msg, tf_buffer);
  47. //}
  48. std::size_t VoxelGenerator::pointsToVoxels(
  49. std::vector<float> & voxels, std::vector<int> & coordinates,
  50. std::vector<float> & num_points_per_voxel)
  51. {
  52. // voxels (float): (max_voxel_size * max_point_in_voxel_size * point_feature_size)
  53. // coordinates (int): (max_voxel_size * point_dim_size)
  54. // num_points_per_voxel (float): (max_voxel_size)
  55. const std::size_t grid_size = config_.grid_size_z_ * config_.grid_size_y_ * config_.grid_size_x_;
  56. std::vector<int> coord_to_voxel_idx(grid_size, -1);
  57. std::size_t voxel_cnt = 0; // @return
  58. std::vector<float> point;
  59. point.resize(config_.point_feature_size_);
  60. std::vector<float> coord_zyx;
  61. coord_zyx.resize(config_.point_dim_size_);
  62. bool out_of_range;
  63. std::size_t point_cnt;
  64. int c, coord_idx, voxel_idx;
  65. Eigen::Vector3f point_current, point_past;
  66. for (auto pc_cache_iter = pd_ptr_->getPointCloudCacheIter(); !pd_ptr_->isCacheEnd(pc_cache_iter);
  67. pc_cache_iter++) {
  68. pcl::PointCloud<pcl::PointXYZI>::Ptr pc_ptr = pc_cache_iter->pc_ptr;
  69. int nsize = pc_ptr->points.size();
  70. int i;
  71. for (i=0;i<nsize;i++) {
  72. point[0] = pc_ptr->points.at(i).x;
  73. point[1] = pc_ptr->points.at(i).y;
  74. point[2] = pc_ptr->points.at(i).z;
  75. point[3] = 0;
  76. out_of_range = false;
  77. for (std::size_t di = 0; di < config_.point_dim_size_; di++) {
  78. c = static_cast<int>((point[di] - range_[di]) * recip_voxel_size_[di]);
  79. if (c < 0 || c >= grid_size_[di]) {
  80. out_of_range = true;
  81. break;
  82. }
  83. coord_zyx[config_.point_dim_size_ - di - 1] = c;
  84. }
  85. if (out_of_range) {
  86. continue;
  87. }
  88. coord_idx = coord_zyx[0] * config_.grid_size_y_ * config_.grid_size_x_ +
  89. coord_zyx[1] * config_.grid_size_x_ + coord_zyx[2];
  90. voxel_idx = coord_to_voxel_idx[coord_idx];
  91. if (voxel_idx == -1) {
  92. voxel_idx = voxel_cnt;
  93. if (voxel_cnt >= config_.max_voxel_size_) {
  94. continue;
  95. }
  96. voxel_cnt++;
  97. coord_to_voxel_idx[coord_idx] = voxel_idx;
  98. for (std::size_t di = 0; di < config_.point_dim_size_; di++) {
  99. coordinates[voxel_idx * config_.point_dim_size_ + di] = coord_zyx[di];
  100. }
  101. }
  102. point_cnt = num_points_per_voxel[voxel_idx];
  103. if (point_cnt < config_.max_point_in_voxel_size_) {
  104. for (std::size_t fi = 0; fi < config_.point_feature_size_; fi++) {
  105. voxels
  106. [voxel_idx * config_.max_point_in_voxel_size_ * config_.point_feature_size_ +
  107. point_cnt * config_.point_feature_size_ + fi] = point[fi];
  108. }
  109. num_points_per_voxel[voxel_idx]++;
  110. }
  111. }
  112. }
  113. return voxel_cnt;
  114. }
  115. //std::size_t VoxelGenerator::pointsToVoxels(
  116. // std::vector<float> & voxels, std::vector<int> & coordinates,
  117. // std::vector<float> & num_points_per_voxel)
  118. //{
  119. // // voxels (float): (max_voxel_size * max_point_in_voxel_size * point_feature_size)
  120. // // coordinates (int): (max_voxel_size * point_dim_size)
  121. // // num_points_per_voxel (float): (max_voxel_size)
  122. // const std::size_t grid_size = config_.grid_size_z_ * config_.grid_size_y_ * config_.grid_size_x_;
  123. // std::vector<int> coord_to_voxel_idx(grid_size, -1);
  124. // std::size_t voxel_cnt = 0; // @return
  125. // std::vector<float> point;
  126. // point.resize(config_.point_feature_size_);
  127. // std::vector<float> coord_zyx;
  128. // coord_zyx.resize(config_.point_dim_size_);
  129. // bool out_of_range;
  130. // std::size_t point_cnt;
  131. // int c, coord_idx, voxel_idx;
  132. // Eigen::Vector3f point_current, point_past;
  133. // for (auto pc_cache_iter = pd_ptr_->getPointCloudCacheIter(); !pd_ptr_->isCacheEnd(pc_cache_iter);
  134. // pc_cache_iter++) {
  135. // auto pc_msg = pc_cache_iter->pointcloud_msg;
  136. // auto affine_past2current =
  137. // pd_ptr_->pointcloud_cache_size() > 1
  138. // ? pd_ptr_->getAffineWorldToCurrent() * pc_cache_iter->affine_past2world
  139. // : Eigen::Affine3f::Identity();
  140. // float time_lag = static_cast<float>(
  141. // pd_ptr_->getCurrentTimestamp() - rclcpp::Time(pc_msg.header.stamp).seconds());
  142. // for (sensor_msgs::PointCloud2ConstIterator<float> x_iter(pc_msg, "x"), y_iter(pc_msg, "y"),
  143. // z_iter(pc_msg, "z");
  144. // x_iter != x_iter.end(); ++x_iter, ++y_iter, ++z_iter) {
  145. // point_past << *x_iter, *y_iter, *z_iter;
  146. // point_current = affine_past2current * point_past;
  147. // point[0] = point_current.x();
  148. // point[1] = point_current.y();
  149. // point[2] = point_current.z();
  150. // point[3] = time_lag;
  151. // out_of_range = false;
  152. // for (std::size_t di = 0; di < config_.point_dim_size_; di++) {
  153. // c = static_cast<int>((point[di] - range_[di]) * recip_voxel_size_[di]);
  154. // if (c < 0 || c >= grid_size_[di]) {
  155. // out_of_range = true;
  156. // break;
  157. // }
  158. // coord_zyx[config_.point_dim_size_ - di - 1] = c;
  159. // }
  160. // if (out_of_range) {
  161. // continue;
  162. // }
  163. // coord_idx = coord_zyx[0] * config_.grid_size_y_ * config_.grid_size_x_ +
  164. // coord_zyx[1] * config_.grid_size_x_ + coord_zyx[2];
  165. // voxel_idx = coord_to_voxel_idx[coord_idx];
  166. // if (voxel_idx == -1) {
  167. // voxel_idx = voxel_cnt;
  168. // if (voxel_cnt >= config_.max_voxel_size_) {
  169. // continue;
  170. // }
  171. // voxel_cnt++;
  172. // coord_to_voxel_idx[coord_idx] = voxel_idx;
  173. // for (std::size_t di = 0; di < config_.point_dim_size_; di++) {
  174. // coordinates[voxel_idx * config_.point_dim_size_ + di] = coord_zyx[di];
  175. // }
  176. // }
  177. // point_cnt = num_points_per_voxel[voxel_idx];
  178. // if (point_cnt < config_.max_point_in_voxel_size_) {
  179. // for (std::size_t fi = 0; fi < config_.point_feature_size_; fi++) {
  180. // voxels
  181. // [voxel_idx * config_.max_point_in_voxel_size_ * config_.point_feature_size_ +
  182. // point_cnt * config_.point_feature_size_ + fi] = point[fi];
  183. // }
  184. // num_points_per_voxel[voxel_idx]++;
  185. // }
  186. // }
  187. // }
  188. // return voxel_cnt;
  189. //}
  190. } // namespace centerpoint