octree.h
Go to the documentation of this file.
1 // kate: replace-tabs off; indent-width 4; indent-mode normal
2 // vim: ts=4:sw=4:noexpandtab
3 /*
4 
5 Copyright (c) 2010--2018,
6 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
7 You can contact the authors at <f dot pomerleau at gmail dot com> and
8 <stephane at magnenat dot net>
9 
10 All rights reserved.
11 
12 Redistribution and use in source and binary forms, with or without
13 modification, are permitted provided that the following conditions are met:
14  * Redistributions of source code must retain the above copyright
15  notice, this list of conditions and the following disclaimer.
16  * Redistributions in binary form must reproduce the above copyright
17  notice, this list of conditions and the following disclaimer in the
18  documentation and/or other materials provided with the distribution.
19  * Neither the name of the <organization> nor the
20  names of its contributors may be used to endorse or promote products
21  derived from this software without specific prior written permission.
22 
23 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
24 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
25 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
26 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
27 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
28 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
30 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
31 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
32 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
33 
34 */
35 #pragma once
36 
37 #include <cstdlib>
38 #include <vector>
39 #include "PointMatcher.h"
40 
41 #include "utils.h"
42 
77 template < typename T, std::size_t dim >
78 class Octree_
79 {
80 public:
82  using DP = typename PM::DataPoints;
83  using Id = typename DP::Index;
84 
85  using Data = typename DP::Index;
86  using DataContainer = std::vector<Data>;
87 
88  using Point = Eigen::Matrix<T,dim,1>;
89 
90 //private:
91  static constexpr std::size_t nbCells = PointMatcherSupport::pow(2, dim);
92 
93 private:
94  struct BoundingBox
95  {
98  };
99 
102 
103  /******************************************************
104  * Cells id are assigned as their position
105  * from the center (+ greater than center, - lower than center)
106  *
107  * for 3D case for 2D case
108  *
109  * 0 1 2 3 4 5 6 7 0 1 2 3
110  * x: - + - + - + - + x: - + - +
111  * y: - - + + - - + + y: - - + +
112  * z: - - - - + + + +
113  *
114  *****************************************************/
115 
116  BoundingBox bb;
117 
119 
120  std::size_t depth;
121 
122 public:
123  Octree_();
124  Octree_(const Octree_<T,dim>& o); //Deep-copy
125  Octree_(Octree_<T,dim>&& o);
126 
127  virtual ~Octree_();
128 
129  Octree_<T,dim>& operator=(const Octree_<T,dim>& o);//Deep-copy
131 
132  bool isLeaf() const;
133  bool isRoot() const;
134  bool isEmpty()const;
135 
136  inline std::size_t idx(const Point& pt) const;
137  inline std::size_t idx(const DP& pts, const Data d) const;
138 
139  std::size_t getDepth() const;
140 
141  T getRadius() const;
142  Point getCenter() const;
143 
145  Octree_<T, dim>* operator[](std::size_t idx);
146 
147  // Build tree from DataPoints with a specified stop parameter
148  bool build(const DP& pts, size_t maxDataByNode=1, T maxSizeByNode=T(0.), bool parallelBuild=false);
149 
150 protected:
151  //real build function
152  bool build(const DP& pts, DataContainer&& datas, BoundingBox&& bb, size_t maxDataByNode=1, T maxSizeByNode=T(0.), bool parallelBuild=false);
153 
154  inline DataContainer toData(const DP& pts, const std::vector<Id>& ids);
155 
156 public:
157  template < typename Callback >
158  bool visit(Callback& cb);
159 };
160 
161 #include "octree.hpp"
162 
163 template<typename T> using Quadtree = Octree_<T,2>;
164 template<typename T> using Octree = Octree_<T,3>;
165 
Octree_::isLeaf
bool isLeaf() const
Definition: octree.hpp:166
Octree_::getRadius
T getRadius() const
Definition: octree.hpp:202
Octree_::Octree_
Octree_()
Definition: octree.hpp:42
Octree_::depth
std::size_t depth
Definition: octree.h:120
Octree_::build
bool build(const DP &pts, size_t maxDataByNode=1, T maxSizeByNode=T(0.), bool parallelBuild=false)
Definition: octree.hpp:231
build_map.T
T
Definition: build_map.py:34
DataPoints
PM::DataPoints DataPoints
Definition: pypoint_matcher_helper.h:16
Octree_::getCenter
Point getCenter() const
Definition: octree.hpp:207
octree.hpp
Octree_::~Octree_
virtual ~Octree_()
Definition: octree.hpp:97
Octree_::operator[]
Octree_< T, dim > * operator[](std::size_t idx)
Definition: octree.hpp:217
PointMatcher
Functions and classes that are dependant on scalar type are defined in this templatized class.
Definition: PointMatcher.h:130
Octree_< T, 2 >::Point
Eigen::Matrix< T, dim, 1 > Point
Definition: octree.h:88
Octree_::operator=
Octree_< T, dim > & operator=(const Octree_< T, dim > &o)
Definition: octree.hpp:106
utils.h
Octree_::BoundingBox
Definition: octree.h:94
Octree_< T, 2 >::Data
typename DP::Index Data
Definition: octree.h:85
Octree_::parent
Octree_ * parent
Definition: octree.h:100
Octree_::isRoot
bool isRoot() const
Definition: octree.hpp:171
Octree_< T, 2 >::DP
typename PM::DataPoints DP
Definition: octree.h:82
Octree_< T, 2 >::DataContainer
std::vector< Data > DataContainer
Definition: octree.h:86
Octree_< T, 2 >::Id
typename DP::Index Id
Definition: octree.h:83
Octree_::bb
BoundingBox bb
Definition: octree.h:116
Octree_::getDepth
std::size_t getDepth() const
Definition: octree.hpp:197
Octree_::visit
bool visit(Callback &cb)
Definition: octree.hpp:373
PointMatcher::DataPoints::Index
Matrix::Index Index
An index to a row or a column.
Definition: PointMatcher.h:218
Octree_::isEmpty
bool isEmpty() const
Definition: octree.hpp:176
Octree_::idx
std::size_t idx(const Point &pt) const
Definition: octree.hpp:181
Octree_::nbCells
static constexpr std::size_t nbCells
Definition: octree.h:91
Octree_::data
DataContainer data
Definition: octree.h:118
icp_advance_api.dim
dim
Definition: icp_advance_api.py:152
Octree_
Definition: octree.h:78
Octree_::BoundingBox::center
Point center
Definition: octree.h:96
Octree_::cells
Octree_ * cells[nbCells]
Definition: octree.h:101
Octree_::toData
DataContainer toData(const DP &pts, const std::vector< Id > &ids)
Definition: octree.hpp:224
PointMatcher.h
public interface
Octree_::BoundingBox::radius
T radius
Definition: octree.h:97
Octree_::getData
DataContainer * getData()
Definition: octree.hpp:212
PointMatcherSupport::pow
constexpr T pow(const T base, const std::size_t exponent)
Definition: utils.h:47


libpointmatcher
Author(s):
autogenerated on Mon Jan 1 2024 03:24:43