30 #ifndef MCL_3DL_CHUNKED_KDTREE_H
31 #define MCL_3DL_CHUNKED_KDTREE_H
36 #include <unordered_map>
39 #include <pcl/point_types.h>
40 #include <pcl/kdtree/kdtree.h>
41 #include <pcl/kdtree/kdtree_flann.h>
45 template <
typename POINT_TYPE>
49 using Ptr = std::shared_ptr<ChunkedKdtree>;
54 using Ptr = std::shared_ptr<ChunkId>;
74 return (
id.
x_) ^ (
id.y_ << 11) ^ (
id.
z_ << 22);
76 ChunkId(
const int x,
const int y,
const int z)
91 const float chunk_length = 20.0,
92 const float max_search_radius = 1.0,
93 const bool keep_clouds =
false)
108 chunk.second.kdtree_->setEpsilon(
epsilon_);
112 const typename pcl::PointRepresentation<POINT_TYPE>::ConstPtr point_rep)
117 chunk.second.kdtree_->setPointRepresentation(
point_rep_);
125 const typename pcl::PointCloud<POINT_TYPE>::ConstPtr& cloud)
133 for (
auto& p : *cloud)
136 clouds[chunk_id].push_back(p);
137 ids[chunk_id].push_back(i);
160 if (x_bound && y_bound && z_bound)
162 const ChunkId id(chunk_id + ChunkId(x_bound, y_bound, z_bound));
163 clouds[id].push_back(p);
164 ids[id].push_back(i);
166 if (x_bound && y_bound)
168 const ChunkId id(chunk_id + ChunkId(x_bound, y_bound, 0));
169 clouds[id].push_back(p);
170 ids[id].push_back(i);
172 if (y_bound && z_bound)
174 const ChunkId id(chunk_id + ChunkId(0, y_bound, z_bound));
175 clouds[id].push_back(p);
176 ids[id].push_back(i);
178 if (z_bound && x_bound)
180 const ChunkId id(chunk_id + ChunkId(x_bound, 0, z_bound));
181 clouds[id].push_back(p);
182 ids[id].push_back(i);
186 const ChunkId id(chunk_id + ChunkId(x_bound, 0, 0));
187 clouds[id].push_back(p);
188 ids[id].push_back(i);
192 const ChunkId id(chunk_id + ChunkId(0, y_bound, 0));
193 clouds[id].push_back(p);
194 ids[id].push_back(i);
198 const ChunkId id(chunk_id + ChunkId(0, 0, z_bound));
199 clouds[id].push_back(p);
200 ids[id].push_back(i);
204 for (
auto& cloud : clouds)
210 auto cloud_ptr = cloud.second.makeShared();
211 chunks_[cloud.first].kdtree_->setInputCloud(cloud_ptr);
213 chunks_[cloud.first].cloud_ = cloud_ptr;
214 chunks_[cloud.first].original_ids_ = ids[cloud.first];
220 std::vector<int>&
id,
221 std::vector<float>& dist_sq,
225 throw std::runtime_error(
"ChunkedKdtree: radius must be <chunk_length");
231 const auto ret =
chunks_[chunk_id].kdtree_->radiusSearch(p, radius,
id, dist_sq, num);
234 i =
chunks_[chunk_id].original_ids_[i];
245 return typename pcl::KdTreeFLANN<POINT_TYPE>::Ptr();
248 typename pcl::PointCloud<POINT_TYPE>::Ptr
getChunkCloud(
const POINT_TYPE& p)
255 return typename pcl::PointCloud<POINT_TYPE>::Ptr();
260 return ChunkId(
static_cast<int>(std::floor(p.x *
pos_to_chunk_)),
269 typename pcl::KdTreeFLANN<POINT_TYPE>::Ptr
kdtree_;
271 typename pcl::PointCloud<POINT_TYPE>::Ptr
cloud_;
286 typename pcl::PointRepresentation<POINT_TYPE>::ConstPtr
point_rep_;
288 using ChunkMap = std::unordered_map<ChunkId, Chunk, ChunkId>;
289 using ChunkCloud = std::unordered_map<ChunkId, typename pcl::PointCloud<POINT_TYPE>, ChunkId>;
296 #endif // MCL_3DL_CHUNKED_KDTREE_H