voxel_generator.cpp 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130
  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. namespace centerpoint
  17. {
  18. VoxelGeneratorTemplate::VoxelGeneratorTemplate(
  19. const DensificationParam & param, const CenterPointConfig & config)
  20. : config_(config)
  21. {
  22. pd_ptr_ = std::make_unique<PointCloudDensification>(param);
  23. range_[0] = config.range_min_x_;
  24. range_[1] = config.range_min_y_;
  25. range_[2] = config.range_min_z_;
  26. range_[3] = config.range_max_x_;
  27. range_[4] = config.range_max_y_;
  28. range_[5] = config.range_max_z_;
  29. grid_size_[0] = config.grid_size_x_;
  30. grid_size_[1] = config.grid_size_y_;
  31. grid_size_[2] = config.grid_size_z_;
  32. recip_voxel_size_[0] = 1 / config.voxel_size_x_;
  33. recip_voxel_size_[1] = 1 / config.voxel_size_y_;
  34. recip_voxel_size_[2] = 1 / config.voxel_size_z_;
  35. }
  36. bool VoxelGeneratorTemplate::enqueuePointCloud(
  37. const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer)
  38. {
  39. return pd_ptr_->enqueuePointCloud(input_pointcloud_msg, tf_buffer);
  40. }
  41. std::size_t VoxelGenerator::pointsToVoxels(
  42. std::vector<float> & voxels, std::vector<int> & coordinates,
  43. std::vector<float> & num_points_per_voxel)
  44. {
  45. // voxels (float): (max_voxel_size * max_point_in_voxel_size * point_feature_size)
  46. // coordinates (int): (max_voxel_size * point_dim_size)
  47. // num_points_per_voxel (float): (max_voxel_size)
  48. const std::size_t grid_size = config_.grid_size_z_ * config_.grid_size_y_ * config_.grid_size_x_;
  49. std::vector<int> coord_to_voxel_idx(grid_size, -1);
  50. std::size_t voxel_cnt = 0; // @return
  51. std::vector<float> point;
  52. point.resize(config_.point_feature_size_);
  53. std::vector<float> coord_zyx;
  54. coord_zyx.resize(config_.point_dim_size_);
  55. bool out_of_range;
  56. std::size_t point_cnt;
  57. int c, coord_idx, voxel_idx;
  58. Eigen::Vector3f point_current, point_past;
  59. for (auto pc_cache_iter = pd_ptr_->getPointCloudCacheIter(); !pd_ptr_->isCacheEnd(pc_cache_iter);
  60. pc_cache_iter++) {
  61. auto pc_msg = pc_cache_iter->pointcloud_msg;
  62. auto affine_past2current =
  63. pd_ptr_->getAffineWorldToCurrent() * pc_cache_iter->affine_past2world;
  64. float timelag = static_cast<float>(
  65. pd_ptr_->getCurrentTimestamp() - rclcpp::Time(pc_msg.header.stamp).seconds());
  66. for (sensor_msgs::PointCloud2ConstIterator<float> x_iter(pc_msg, "x"), y_iter(pc_msg, "y"),
  67. z_iter(pc_msg, "z");
  68. x_iter != x_iter.end(); ++x_iter, ++y_iter, ++z_iter) {
  69. point_past << *x_iter, *y_iter, *z_iter;
  70. point_current = affine_past2current * point_past;
  71. point[0] = point_current.x();
  72. point[1] = point_current.y();
  73. point[2] = point_current.z();
  74. point[3] = timelag;
  75. out_of_range = false;
  76. for (std::size_t di = 0; di < config_.point_dim_size_; di++) {
  77. c = static_cast<int>((point[di] - range_[di]) * recip_voxel_size_[di]);
  78. if (c < 0 || c >= grid_size_[di]) {
  79. out_of_range = true;
  80. break;
  81. }
  82. coord_zyx[config_.point_dim_size_ - di - 1] = c;
  83. }
  84. if (out_of_range) {
  85. continue;
  86. }
  87. coord_idx = coord_zyx[0] * config_.grid_size_y_ * config_.grid_size_x_ +
  88. coord_zyx[1] * config_.grid_size_x_ + coord_zyx[2];
  89. voxel_idx = coord_to_voxel_idx[coord_idx];
  90. if (voxel_idx == -1) {
  91. voxel_idx = voxel_cnt;
  92. if (voxel_cnt >= config_.max_voxel_size_) {
  93. continue;
  94. }
  95. voxel_cnt++;
  96. coord_to_voxel_idx[coord_idx] = voxel_idx;
  97. for (std::size_t di = 0; di < config_.point_dim_size_; di++) {
  98. coordinates[voxel_idx * config_.point_dim_size_ + di] = coord_zyx[di];
  99. }
  100. }
  101. point_cnt = num_points_per_voxel[voxel_idx];
  102. if (point_cnt < config_.max_point_in_voxel_size_) {
  103. for (std::size_t fi = 0; fi < config_.point_feature_size_; fi++) {
  104. voxels
  105. [voxel_idx * config_.max_point_in_voxel_size_ * config_.point_feature_size_ +
  106. point_cnt * config_.point_feature_size_ + fi] = point[fi];
  107. }
  108. num_points_per_voxel[voxel_idx]++;
  109. }
  110. }
  111. }
  112. return voxel_cnt;
  113. }
  114. } // namespace centerpoint