00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef MCL_3DL_CHUNKED_KDTREE_H
00031 #define MCL_3DL_CHUNKED_KDTREE_H
00032
00033 #include <pcl/point_types.h>
00034 #include <pcl/kdtree/kdtree.h>
00035 #include <pcl/kdtree/kdtree_flann.h>
00036
00037 #include <stdexcept>
00038 #include <unordered_map>
00039 #include <vector>
00040
00041 namespace mcl_3dl
00042 {
00043 template <typename POINT_TYPE>
00044 class ChunkedKdtree
00045 {
00046 public:
00047 using Ptr = std::shared_ptr<ChunkedKdtree>;
00048
00049 class ChunkId
00050 {
00051 public:
00052 using Ptr = std::shared_ptr<ChunkId>;
00053
00054 const int x_;
00055 const int y_;
00056 const int z_;
00057
00058 constexpr bool operator==(const ChunkId& a) const
00059 {
00060 return x_ == a.x_ && y_ == a.y_ && z_ == a.z_;
00061 }
00062 constexpr bool operator!=(const ChunkId& a) const
00063 {
00064 return !operator==(a);
00065 }
00066 constexpr ChunkId operator+(const ChunkId& a) const
00067 {
00068 return ChunkId(x_ + a.x_, y_ + a.y_, z_ + a.z_);
00069 }
00070 size_t operator()(const ChunkId& id) const
00071 {
00072 return (id.x_) ^ (id.y_ << 11) ^ (id.z_ << 22);
00073 }
00074 ChunkId(const int& x, const int& y, const int& z)
00075 : x_(x)
00076 , y_(y)
00077 , z_(z)
00078 {
00079 }
00080 ChunkId()
00081 : x_(0)
00082 , y_(0)
00083 , z_(0)
00084 {
00085 }
00086 };
00087
00088 explicit ChunkedKdtree(
00089 const float chunk_length = 20.0,
00090 const float max_search_radius = 1.0,
00091 const bool keep_clouds = false)
00092 : pos_to_chunk_(1.0 / chunk_length)
00093 , chunk_length_(chunk_length)
00094 , max_search_radius_(max_search_radius)
00095 , set_epsilon_(false)
00096 , keep_clouds_(keep_clouds)
00097 {
00098 chunks_.clear();
00099 }
00100 void setEpsilon(const float epsilon)
00101 {
00102 epsilon_ = epsilon;
00103 set_epsilon_ = true;
00104 for (auto& chunk : chunks_)
00105 {
00106 chunk.second.kdtree_->setEpsilon(epsilon_);
00107 }
00108 }
00109 void setPointRepresentation(
00110 boost::shared_ptr<pcl::PointRepresentation<POINT_TYPE>> point_rep)
00111 {
00112 point_rep_ = point_rep;
00113 for (auto& chunk : chunks_)
00114 {
00115 chunk.second.kdtree_->setPointRepresentation(point_rep_);
00116 }
00117 }
00118 void setInputCloud(
00119 const typename pcl::PointCloud<POINT_TYPE>::ConstPtr cloud)
00120 {
00121 if (chunks_.size())
00122 chunks_.clear();
00123 ChunkOriginalIds ids;
00124 ChunkCloud clouds;
00125 size_t i = 0;
00126 for (auto& p : *cloud)
00127 {
00128 const auto chunk_id = getChunkId(p);
00129 clouds[chunk_id].push_back(p);
00130 ids[chunk_id].push_back(i);
00131
00132 const float in_chunk_x = p.x - chunk_id.x_ * chunk_length_;
00133 int x_bound = 0;
00134 if (in_chunk_x < max_search_radius_)
00135 x_bound = -1;
00136 else if (in_chunk_x > chunk_length_ - max_search_radius_)
00137 x_bound = 1;
00138
00139 const float in_chunk_y = p.y - chunk_id.y_ * chunk_length_;
00140 int y_bound = 0;
00141 if (in_chunk_y < max_search_radius_)
00142 y_bound = -1;
00143 else if (in_chunk_y > chunk_length_ - max_search_radius_)
00144 y_bound = 1;
00145
00146 const float in_chunk_z = p.z - chunk_id.z_ * chunk_length_;
00147 int z_bound = 0;
00148 if (in_chunk_z < max_search_radius_)
00149 z_bound = -1;
00150 else if (in_chunk_z > chunk_length_ - max_search_radius_)
00151 z_bound = 1;
00152
00153 if (x_bound && y_bound && z_bound)
00154 {
00155 const ChunkId id(chunk_id + ChunkId(x_bound, y_bound, z_bound));
00156 clouds[id].push_back(p);
00157 ids[id].push_back(i);
00158 }
00159 if (x_bound && y_bound)
00160 {
00161 const ChunkId id(chunk_id + ChunkId(x_bound, y_bound, 0));
00162 clouds[id].push_back(p);
00163 ids[id].push_back(i);
00164 }
00165 if (y_bound && z_bound)
00166 {
00167 const ChunkId id(chunk_id + ChunkId(0, y_bound, z_bound));
00168 clouds[id].push_back(p);
00169 ids[id].push_back(i);
00170 }
00171 if (z_bound && x_bound)
00172 {
00173 const ChunkId id(chunk_id + ChunkId(x_bound, 0, z_bound));
00174 clouds[id].push_back(p);
00175 ids[id].push_back(i);
00176 }
00177 if (x_bound)
00178 {
00179 const ChunkId id(chunk_id + ChunkId(x_bound, 0, 0));
00180 clouds[id].push_back(p);
00181 ids[id].push_back(i);
00182 }
00183 if (y_bound)
00184 {
00185 const ChunkId id(chunk_id + ChunkId(0, y_bound, 0));
00186 clouds[id].push_back(p);
00187 ids[id].push_back(i);
00188 }
00189 if (z_bound)
00190 {
00191 const ChunkId id(chunk_id + ChunkId(0, 0, z_bound));
00192 clouds[id].push_back(p);
00193 ids[id].push_back(i);
00194 }
00195 ++i;
00196 }
00197 for (auto& cloud : clouds)
00198 {
00199 if (point_rep_)
00200 chunks_[cloud.first].kdtree_->setPointRepresentation(point_rep_);
00201 if (set_epsilon_)
00202 chunks_[cloud.first].kdtree_->setEpsilon(epsilon_);
00203 auto cloud_ptr = cloud.second.makeShared();
00204 chunks_[cloud.first].kdtree_->setInputCloud(cloud_ptr);
00205 if (keep_clouds_)
00206 chunks_[cloud.first].cloud_ = cloud_ptr;
00207 chunks_[cloud.first].original_ids_ = ids[cloud.first];
00208 }
00209 }
00210 int radiusSearch(
00211 const POINT_TYPE& p,
00212 const float& radius,
00213 std::vector<int>& id,
00214 std::vector<float>& dist_sq,
00215 const size_t& num)
00216 {
00217 if (radius > chunk_length_)
00218 throw std::runtime_error("ChunkedKdtree: radius must be <chunk_length");
00219
00220 const auto chunk_id = getChunkId(p);
00221 if (chunks_.find(chunk_id) == chunks_.end())
00222 return false;
00223
00224 const auto ret = chunks_[chunk_id].kdtree_->radiusSearch(p, radius, id, dist_sq, num);
00225
00226 for (auto& i : id)
00227 i = chunks_[chunk_id].original_ids_[i];
00228
00229 return ret;
00230 }
00231 typename pcl::KdTreeFLANN<POINT_TYPE>::Ptr getChunkKdtree(const POINT_TYPE p)
00232 {
00233 return getChunkKdtree(getChunkId(p));
00234 }
00235 typename pcl::KdTreeFLANN<POINT_TYPE>::Ptr getChunkKdtree(const ChunkId& c)
00236 {
00237 if (chunks_.find(c) == chunks_.end())
00238 return typename pcl::KdTreeFLANN<POINT_TYPE>::Ptr();
00239 return chunks_[c].kdtree_;
00240 }
00241 typename pcl::PointCloud<POINT_TYPE>::Ptr getChunkCloud(const POINT_TYPE p)
00242 {
00243 return getChunkCloud(getChunkId(p));
00244 }
00245 typename pcl::PointCloud<POINT_TYPE>::Ptr getChunkCloud(const ChunkId& c)
00246 {
00247 if (!keep_clouds_ || chunks_.find(c) == chunks_.end())
00248 return typename pcl::PointCloud<POINT_TYPE>::Ptr();
00249 return chunks_[c].cloud_;
00250 }
00251 ChunkId getChunkId(const POINT_TYPE p) const
00252 {
00253 return ChunkId(static_cast<int>(floor(p.x * pos_to_chunk_)),
00254 static_cast<int>(floor(p.y * pos_to_chunk_)),
00255 static_cast<int>(floor(p.z * pos_to_chunk_)));
00256 }
00257
00258 protected:
00259 class Chunk
00260 {
00261 public:
00262 typename pcl::KdTreeFLANN<POINT_TYPE>::Ptr kdtree_;
00263 std::vector<size_t> original_ids_;
00264 typename pcl::PointCloud<POINT_TYPE>::Ptr cloud_;
00265
00266 Chunk()
00267 : kdtree_(new pcl::KdTreeFLANN<POINT_TYPE>)
00268 , cloud_(new pcl::PointCloud<POINT_TYPE>)
00269 {
00270 }
00271 };
00272
00273 const float pos_to_chunk_;
00274 const float chunk_length_;
00275 const float max_search_radius_;
00276 bool set_epsilon_;
00277 bool keep_clouds_;
00278 float epsilon_;
00279 boost::shared_ptr<pcl::PointRepresentation<POINT_TYPE>> point_rep_;
00280
00281 using ChunkMap = std::unordered_map<ChunkId, Chunk, ChunkId>;
00282 using ChunkCloud = std::unordered_map<ChunkId, typename pcl::PointCloud<POINT_TYPE>, ChunkId>;
00283 using ChunkOriginalIds = std::unordered_map<ChunkId, std::vector<size_t>, ChunkId>;
00284 ChunkMap chunks_;
00285 };
00286 }
00287
00288 #endif // MCL_3DL_CHUNKED_KDTREE_H