chunked_kdtree.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, the mcl_3dl authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef MCL_3DL_CHUNKED_KDTREE_H
31 #define MCL_3DL_CHUNKED_KDTREE_H
32 
33 #include <pcl/point_types.h>
34 #include <pcl/kdtree/kdtree.h>
35 #include <pcl/kdtree/kdtree_flann.h>
36 
37 #include <stdexcept>
38 #include <unordered_map>
39 #include <vector>
40 
41 namespace mcl_3dl
42 {
43 template <typename POINT_TYPE>
45 {
46 public:
47  using Ptr = std::shared_ptr<ChunkedKdtree>;
48 
49  class ChunkId
50  {
51  public:
52  using Ptr = std::shared_ptr<ChunkId>;
53 
54  const int x_;
55  const int y_;
56  const int z_;
57 
58  constexpr bool operator==(const ChunkId& a) const
59  {
60  return x_ == a.x_ && y_ == a.y_ && z_ == a.z_;
61  }
62  constexpr bool operator!=(const ChunkId& a) const
63  {
64  return !operator==(a);
65  }
66  constexpr ChunkId operator+(const ChunkId& a) const
67  {
68  return ChunkId(x_ + a.x_, y_ + a.y_, z_ + a.z_);
69  }
70  size_t operator()(const ChunkId& id) const
71  {
72  return (id.x_) ^ (id.y_ << 11) ^ (id.z_ << 22);
73  }
74  ChunkId(const int& x, const int& y, const int& z)
75  : x_(x)
76  , y_(y)
77  , z_(z)
78  {
79  }
81  : x_(0)
82  , y_(0)
83  , z_(0)
84  {
85  }
86  };
87 
88  explicit ChunkedKdtree(
89  const float chunk_length = 20.0,
90  const float max_search_radius = 1.0,
91  const bool keep_clouds = false)
92  : pos_to_chunk_(1.0 / chunk_length)
93  , chunk_length_(chunk_length)
94  , max_search_radius_(max_search_radius)
95  , set_epsilon_(false)
96  , keep_clouds_(keep_clouds)
97  {
98  chunks_.clear();
99  }
100  void setEpsilon(const float epsilon)
101  {
102  epsilon_ = epsilon;
103  set_epsilon_ = true;
104  for (auto& chunk : chunks_)
105  {
106  chunk.second.kdtree_->setEpsilon(epsilon_);
107  }
108  }
110  boost::shared_ptr<pcl::PointRepresentation<POINT_TYPE>> point_rep)
111  {
112  point_rep_ = point_rep;
113  for (auto& chunk : chunks_)
114  {
115  chunk.second.kdtree_->setPointRepresentation(point_rep_);
116  }
117  }
119  const typename pcl::PointCloud<POINT_TYPE>::ConstPtr cloud)
120  {
121  if (chunks_.size())
122  chunks_.clear();
123  ChunkOriginalIds ids;
124  ChunkCloud clouds;
125  size_t i = 0;
126  for (auto& p : *cloud)
127  {
128  const auto chunk_id = getChunkId(p);
129  clouds[chunk_id].push_back(p);
130  ids[chunk_id].push_back(i);
131 
132  const float in_chunk_x = p.x - chunk_id.x_ * chunk_length_;
133  int x_bound = 0;
134  if (in_chunk_x < max_search_radius_)
135  x_bound = -1;
136  else if (in_chunk_x > chunk_length_ - max_search_radius_)
137  x_bound = 1;
138 
139  const float in_chunk_y = p.y - chunk_id.y_ * chunk_length_;
140  int y_bound = 0;
141  if (in_chunk_y < max_search_radius_)
142  y_bound = -1;
143  else if (in_chunk_y > chunk_length_ - max_search_radius_)
144  y_bound = 1;
145 
146  const float in_chunk_z = p.z - chunk_id.z_ * chunk_length_;
147  int z_bound = 0;
148  if (in_chunk_z < max_search_radius_)
149  z_bound = -1;
150  else if (in_chunk_z > chunk_length_ - max_search_radius_)
151  z_bound = 1;
152 
153  if (x_bound && y_bound && z_bound)
154  {
155  const ChunkId id(chunk_id + ChunkId(x_bound, y_bound, z_bound));
156  clouds[id].push_back(p);
157  ids[id].push_back(i);
158  }
159  if (x_bound && y_bound)
160  {
161  const ChunkId id(chunk_id + ChunkId(x_bound, y_bound, 0));
162  clouds[id].push_back(p);
163  ids[id].push_back(i);
164  }
165  if (y_bound && z_bound)
166  {
167  const ChunkId id(chunk_id + ChunkId(0, y_bound, z_bound));
168  clouds[id].push_back(p);
169  ids[id].push_back(i);
170  }
171  if (z_bound && x_bound)
172  {
173  const ChunkId id(chunk_id + ChunkId(x_bound, 0, z_bound));
174  clouds[id].push_back(p);
175  ids[id].push_back(i);
176  }
177  if (x_bound)
178  {
179  const ChunkId id(chunk_id + ChunkId(x_bound, 0, 0));
180  clouds[id].push_back(p);
181  ids[id].push_back(i);
182  }
183  if (y_bound)
184  {
185  const ChunkId id(chunk_id + ChunkId(0, y_bound, 0));
186  clouds[id].push_back(p);
187  ids[id].push_back(i);
188  }
189  if (z_bound)
190  {
191  const ChunkId id(chunk_id + ChunkId(0, 0, z_bound));
192  clouds[id].push_back(p);
193  ids[id].push_back(i);
194  }
195  ++i;
196  }
197  for (auto& cloud : clouds)
198  {
199  if (point_rep_)
200  chunks_[cloud.first].kdtree_->setPointRepresentation(point_rep_);
201  if (set_epsilon_)
202  chunks_[cloud.first].kdtree_->setEpsilon(epsilon_);
203  auto cloud_ptr = cloud.second.makeShared();
204  chunks_[cloud.first].kdtree_->setInputCloud(cloud_ptr);
205  if (keep_clouds_)
206  chunks_[cloud.first].cloud_ = cloud_ptr;
207  chunks_[cloud.first].original_ids_ = ids[cloud.first];
208  }
209  }
211  const POINT_TYPE& p,
212  const float& radius,
213  std::vector<int>& id,
214  std::vector<float>& dist_sq,
215  const size_t& num)
216  {
217  if (radius > chunk_length_)
218  throw std::runtime_error("ChunkedKdtree: radius must be <chunk_length");
219 
220  const auto chunk_id = getChunkId(p);
221  if (chunks_.find(chunk_id) == chunks_.end())
222  return false;
223 
224  const auto ret = chunks_[chunk_id].kdtree_->radiusSearch(p, radius, id, dist_sq, num);
225 
226  for (auto& i : id)
227  i = chunks_[chunk_id].original_ids_[i];
228 
229  return ret;
230  }
231  typename pcl::KdTreeFLANN<POINT_TYPE>::Ptr getChunkKdtree(const POINT_TYPE p)
232  {
233  return getChunkKdtree(getChunkId(p));
234  }
235  typename pcl::KdTreeFLANN<POINT_TYPE>::Ptr getChunkKdtree(const ChunkId& c)
236  {
237  if (chunks_.find(c) == chunks_.end())
238  return typename pcl::KdTreeFLANN<POINT_TYPE>::Ptr();
239  return chunks_[c].kdtree_;
240  }
241  typename pcl::PointCloud<POINT_TYPE>::Ptr getChunkCloud(const POINT_TYPE p)
242  {
243  return getChunkCloud(getChunkId(p));
244  }
245  typename pcl::PointCloud<POINT_TYPE>::Ptr getChunkCloud(const ChunkId& c)
246  {
247  if (!keep_clouds_ || chunks_.find(c) == chunks_.end())
248  return typename pcl::PointCloud<POINT_TYPE>::Ptr();
249  return chunks_[c].cloud_;
250  }
251  ChunkId getChunkId(const POINT_TYPE p) const
252  {
253  return ChunkId(static_cast<int>(floor(p.x * pos_to_chunk_)),
254  static_cast<int>(floor(p.y * pos_to_chunk_)),
255  static_cast<int>(floor(p.z * pos_to_chunk_)));
256  }
257 
258 protected:
259  class Chunk
260  {
261  public:
262  typename pcl::KdTreeFLANN<POINT_TYPE>::Ptr kdtree_;
263  std::vector<size_t> original_ids_;
264  typename pcl::PointCloud<POINT_TYPE>::Ptr cloud_;
265 
267  : kdtree_(new pcl::KdTreeFLANN<POINT_TYPE>)
268  , cloud_(new pcl::PointCloud<POINT_TYPE>)
269  {
270  }
271  };
272 
273  const float pos_to_chunk_;
274  const float chunk_length_;
275  const float max_search_radius_;
278  float epsilon_;
280 
281  using ChunkMap = std::unordered_map<ChunkId, Chunk, ChunkId>;
282  using ChunkCloud = std::unordered_map<ChunkId, typename pcl::PointCloud<POINT_TYPE>, ChunkId>;
283  using ChunkOriginalIds = std::unordered_map<ChunkId, std::vector<size_t>, ChunkId>;
285 };
286 } // namespace mcl_3dl
287 
288 #endif // MCL_3DL_CHUNKED_KDTREE_H
std::vector< size_t > original_ids_
pcl::PointCloud< POINT_TYPE >::Ptr getChunkCloud(const ChunkId &c)
std::shared_ptr< ChunkedKdtree > Ptr
pcl::PointCloud< POINT_TYPE >::Ptr getChunkCloud(const POINT_TYPE p)
pcl::KdTreeFLANN< POINT_TYPE >::Ptr getChunkKdtree(const POINT_TYPE p)
sensor_msgs::PointCloud2 PointCloud
std::unordered_map< ChunkId, typename pcl::PointCloud< mcl_3dl::PointXYZIL >, ChunkId > ChunkCloud
pcl::KdTreeFLANN< POINT_TYPE >::Ptr kdtree_
ChunkedKdtree(const float chunk_length=20.0, const float max_search_radius=1.0, const bool keep_clouds=false)
ChunkId getChunkId(const POINT_TYPE p) const
constexpr bool operator!=(const ChunkId &a) const
int radiusSearch(const POINT_TYPE &p, const float &radius, std::vector< int > &id, std::vector< float > &dist_sq, const size_t &num)
std::unordered_map< ChunkId, Chunk, ChunkId > ChunkMap
std::shared_ptr< ChunkId > Ptr
const float max_search_radius_
void setPointRepresentation(boost::shared_ptr< pcl::PointRepresentation< POINT_TYPE >> point_rep)
void setInputCloud(const typename pcl::PointCloud< POINT_TYPE >::ConstPtr cloud)
constexpr ChunkId operator+(const ChunkId &a) const
boost::shared_ptr< pcl::PointRepresentation< POINT_TYPE > > point_rep_
std::unordered_map< ChunkId, std::vector< size_t >, ChunkId > ChunkOriginalIds
pcl::PointCloud< POINT_TYPE >::Ptr cloud_
pcl::KdTreeFLANN< POINT_TYPE >::Ptr getChunkKdtree(const ChunkId &c)
constexpr bool operator==(const ChunkId &a) const
size_t operator()(const ChunkId &id) const
ChunkId(const int &x, const int &y, const int &z)
void setEpsilon(const float epsilon)


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 8 2019 03:32:36