VoxelGrid.hpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T),
5  * Karlsruhe Institute of Technology (KIT), all rights reserved.
6  *
7  * ArmarX is free software; you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License version 2 as
9  * published by the Free Software Foundation.
10  *
11  * ArmarX is distributed in the hope that it will be useful, but
12  * WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with this program. If not, see <http://www.gnu.org/licenses/>.
18  *
19  * @author Rainer Kartmann (rainer dot kartmann at student dot kit dot edu)
20  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
21  * GNU General Public License
22  */
23 
24 #pragma once
25 
26 #include <vector>
27 
28 #include <Eigen/Geometry>
29 
30 #include "exceptions.h"
31 #include "VoxelGridStructure.h"
32 
33 
34 namespace visionx::voxelgrid
35 {
36 
37  /**
38  * @brief A 3D grid of voxels of type _VoxelT.
39  *
40  * A `VoxelGrid` three-dimensional regular grid of cuboids, called voxels.
41  * Its geometric structure is defined by a `VoxelGridStructure`.
42  * In addition, it stores voxel data of type _VoxelT (one per voxel).
43  *
44  * This is a generic implementation made to hold hold arbitrary data.
45  * As such, there is no concept of "free/occupied" voxels".
46  *
47  * @see VoxelGridStructure
48  */
49  template <typename _VoxelT>
50  class VoxelGrid
51  {
52  public:
53 
54  /// The voxel type.
55  using VoxelT = _VoxelT;
56 
57 
58  public:
59 
60  /// Construct a voxel grid with 0 voxels of size 1.0.
61  VoxelGrid();
62 
63  /// Construct a voxel grid with the given structure and voxels with given value.
64  VoxelGrid(const VoxelGridStructure& structure,
65  const VoxelT& value = {});
66 
67  /**
68  * @brief Construct a voxel grid with the given structure and data.
69  * The size of `voxelData` must match the grid size of `structure`.
70  * @throw error::InvalidVoxelDataSize If the size does not match.
71  */
72  VoxelGrid(const VoxelGridStructure& structure,
73  const std::vector<VoxelGrid::VoxelT>& voxelData);
74 
75  /// Construct a voxel grid with the same structure as other.
76  template <typename OtherVoxelT>
77  VoxelGrid(const VoxelGrid<OtherVoxelT>& other);
78 
79  /// Ordinary copy constructor for voxel grid with same VoxelT.
80  VoxelGrid(const VoxelGrid<VoxelT>& other) = default;
81 
82 
83  /// Reset the voxel data by `numVoxels()` voxels with given value.
84  void reset(const VoxelT& value = {})
85  {
86  _voxels.assign(numVoxels(), value);
87  }
88 
89 
90  /// Get the voxel grid structure.
92  {
93  return _struct;
94  }
95  /// Set the voxel grid structure and reset voxel data.
96  void resetStructure(const VoxelGridStructure& structure)
97  {
98  this->_struct = structure;
99  reset();
100  }
101 
102 
103  /// Get the voxel with the given index. @see `operator[]`
104  VoxelT& getVoxel(std::size_t index)
105  {
106  return _voxels.at(index);
107  }
108  const VoxelT& getVoxel(std::size_t index) const
109  {
110  return _voxels.at(index);
111  }
112 
113  /// Get the voxel with the given grid index. @see `operator[]`
114  VoxelT& getVoxel(int x, int y, int z)
115  {
116  return getVoxel(getVoxelFlatIndex(x, y, z));
117  }
118  const VoxelT& getVoxel(int x, int y, int z) const
119  {
120  return getVoxel(getVoxelFlatIndex(x, y, z));
121  }
122 
123  /// Get the voxel with the given grid index. @see `operator[]`
124  VoxelT& getVoxel(const Eigen::Vector3i& index)
125  {
127  }
128  const VoxelT& getVoxel(const Eigen::Vector3i& index) const
129  {
131  }
132 
133  /// Get the voxel closest to the given point.
134  /// @param local If false (default), the point is transformed to local coordinate system.
135  VoxelT& getVoxel(const Eigen::Vector3f& point, bool local = false)
136  {
137  return getVoxel(getVoxelGridIndex(point, local));
138  }
139  const VoxelT& getVoxel(const Eigen::Vector3f& point, bool local = false) const
140  {
141  return getVoxel(getVoxelGridIndex(point, local));
142  }
143 
144 
145  /// Get the voxels.
146  /// @note `VoxelGrid` provides begin()/end() pairs, so it can be iterated over directly.
147  const std::vector<VoxelT>& getVoxels() const
148  {
149  return _voxels;
150  }
151 
152  /// Set the voxels. (Size must match `numVoxels()`).
153  /// @throw error::InvalidVoxelDataSize If the size does not match.
154  void setVoxels(const std::vector<VoxelT>& voxels)
155  {
156  if (voxels.size() != numVoxels())
157  {
158  throw error::InvalidVoxelDataSize(voxels.size(), numVoxels());
159  }
160  this->_voxels = voxels;
161  }
162 
163 
164  /// Get the number of voxels in the grid.
165  std::size_t numVoxels() const
166  {
167  return getNumVoxels();
168  }
169  /// Get the number of voxels in the grid.
170  std::size_t getNumVoxels() const
171  {
172  return _struct.getNumVoxels();
173  }
174 
175 
176  /// Get the grid size.
177  Eigen::Vector3i getGridSizes() const
178  {
179  return _struct.getGridSize();
180  }
181  /// Set the grid size for a cubic grid. Resets the grid data.
182  void setGridSizes(float gridSizes)
183  {
184  _struct.setGridSize(gridSizes);
185  }
186  /// Set the grid size. This resets the grid data.
187  void setGridSizes(const Eigen::Vector3i& gridSizes)
188  {
189  _struct.setGridSize(gridSizes);
190  reset();
191  }
192 
193 
194  /// Get the voxel size.
195  Eigen::Vector3f getVoxelSizes() const
196  {
197  return _struct.getVoxelSize();
198  }
199  /// Set the voxel size of cubic voxels. The grid data is not updated.
200  void setVoxelSizes(float voxelSize)
201  {
202  _struct.setVoxelSize(voxelSize);
203  }
204  /// Set the voxel size. The grid data is not updated.
205  void setVoxelSizes(const Eigen::Vector3f& voxelSizes)
206  {
207  _struct.setVoxelSize(voxelSizes);
208  }
209 
210 
211  /// Get the flat index of the voxel with given grid index.
212  std::size_t getVoxelFlatIndex(int x, int y, int z) const
213  {
214  return _struct.getFlatIndex(x, y, z);
215  }
216  /// Get the flat index of the voxel with given grid index.
217  std::size_t getVoxelFlatIndex(const Eigen::Vector3i& index) const
218  {
219  return _struct.getFlatIndex(index);
220  }
221  /// Get the flat index of the voxel closest to `point`.
222  std::size_t getVoxelFlatIndex(const Eigen::Vector3f& point, bool local = false) const
223  {
224  return _struct.getFlatIndex(point, local);
225  }
226 
227  /// Get the grid index of the voxel with the given flat index.
228  Eigen::Vector3i getVoxelGridIndex(size_t index) const
229  {
230  return _struct.getGridIndex(index);
231  }
232  /// Get the grid index of the voxel closest to point.
233  /// @param local If false (default), the point is transformed to local coordinate system.
234  Eigen::Vector3i getVoxelGridIndex(const Eigen::Vector3f& point, bool local = false) const
235  {
236  return _struct.getGridIndex(point, local);
237  }
238 
239  /// Get the minimal (along each axis) voxel grid index.
240  Eigen::Vector3i getVoxelGridIndexMin() const
241  {
242  return _struct.getGridIndexMin();
243  }
244  /// Get the maximal (along each axis) voxel grid index.
245  Eigen::Vector3i getVoxelGridIndexMax() const
246  {
247  return _struct.getGridIndexMax();
248  }
249 
250  /// Get the center of the voxel with the given index.
251  Eigen::Vector3f getVoxelCenter(std::size_t index, bool local = false) const
252  {
253  return _struct.getVoxelCenter(index, local);
254  }
255  /// Get the center of the voxel with the given index.
256  Eigen::Vector3f getVoxelCenter(int x, int y, int z, bool local = false) const
257  {
258  return _struct.getVoxelCenter(x, y, z, local);
259  }
260  /// Get the center of the voxel with the given index.
261  Eigen::Vector3f getVoxelCenter(const Eigen::Vector3i& index, bool local = false) const
262  {
263  return _struct.getVoxelCenter(index, local);
264  }
265 
266 
267  /// Get the grid origin in the world frame (center of voxel [0 0 0]).
268  /// Note that this differs from the geometric center for even grid sizes.
269  /// @see getCenter()
270  Eigen::Vector3f getOrigin() const
271  {
272  return _struct.getOrigin();
273  }
274  /// Set the grid origin the world frame (center of voxel [0 0 0]).
275  /// Note that this differs from the geometric center for even grid sizes.
276  /// @see setCenter()
277  void setOrigin(const Eigen::Vector3f& value)
278  {
280  }
281 
282  /// Get the grid orienation in the world frame.
284  {
285  return _struct.getOrientation();
286  }
287  /// Set the grid orienation in the world frame.
289  {
291  }
292 
293  /**
294  * @brief Get the geometric center of the grid the world frame
295  * (which differs from the origin for even grid sizes).
296  */
297  Eigen::Vector3f getCenter() const
298  {
299  return _struct.getCenter();
300  }
301  /**
302  * @brief Set the geometric center of the grid the world frame
303  * (which differs from the origin for even grid sizes).
304  *
305  * @note This computes the origin from the given center using the
306  * current orientation. If you want to set grid center and orientation,
307  * set the orientation first, or (equivalently), use `setCenterPose()`.
308  *
309  * @see setPoseGridCenter()
310  */
311  void setCenter(const Eigen::Vector3f& value)
312  {
314  }
315 
316 
317  /// Get the grid pose in the world frame.
318  /// Note that this differs from the geometric center for even grid sizes.
319  /// @see getCenterPose()
321  {
322  return _struct.getPose();
323  }
324  /// Get the grid pose in the world frame.
325  /// Note that this differs from the geometric center for even grid sizes.
326  /// @see setCenterPose()
328  {
330  }
331 
332  /// Get the grid pose positioned at the grid center in the world frame.
334  {
335  return _struct.getCenterPose();
336  }
337  /// Set the grid pose so that the grid center is the position of the
338  /// given pose under the given orientation.
340  {
342  }
343 
344 
345  /// Get extent of the grid along each axis (encompassing the whole voxels).
346  Eigen::Vector3f getExtents() const
347  {
348  return _struct.getExtent();
349  }
350  /// Get extent of the grid along each axis (encompassing only voxel centers).
351  Eigen::Vector3f getExtentsOfCenters() const
352  {
353  return _struct.getExtentOfCenters();
354  }
355  /// Get the local axis aligned bounding box of the grid (minimal/maximal values in columns).
357  {
358  return _struct.getLocalBoundingBox();
359  }
360  /// Get the local axis aligned bounding box of the voxel centers (minimal/maximal values in columns).
362  {
364  }
365 
366 
367  /// Indicate whether the given point is inside the voxel.
368  bool isInside(const Eigen::Vector3i& index) const
369  {
370  return _struct.isInside(index);
371  }
372  /// Indicate whether the given point is inside the voxel.
373  bool isInside(const Eigen::Vector3f& point, bool local = false) const
374  {
375  return _struct.isInside(point, local);
376  }
377 
378  /// Assert that the given index is a valid grid index.
379  void checkIsInside(const Eigen::Vector3i& index) const
380  {
381  return _struct.checkIsInside(index);
382  }
383 
384 
385  /// Get the voxel with given flat index. @see `getVoxel(std::size_t)`
386  VoxelT& operator[](std::size_t index)
387  {
388  return getVoxel(index);
389  }
390  const VoxelT& operator[](std::size_t index) const
391  {
392  return getVoxel(index);
393  }
394 
395  /// Get the voxel with given grid index. @see `getVoxel(const Eigen::Vector3i&)`
396  VoxelT& operator[](const Eigen::Vector3i& index)
397  {
398  return getVoxel(index);
399  }
400  const VoxelT& operator[](const Eigen::Vector3i& index) const
401  {
402  return getVoxel(index);
403  }
404 
405 
406  /// Get an iterator to the first voxel.
407  typename std::vector<VoxelT>::iterator begin()
408  {
409  return _voxels.begin();
410  }
411  /// Get an iterator to the first voxel.
412  typename std::vector<VoxelT>::const_iterator begin() const
413  {
414  return _voxels.begin();
415  }
416  /// Get an iterator to the first voxel.
417  typename std::vector<VoxelT>::const_iterator cbegin() const
418  {
419  return _voxels.begin();
420  }
421 
422  /// Get an iterator to the element following the last voxel.
423  typename std::vector<VoxelT>::iterator end()
424  {
425  return _voxels.end();
426  }
427  /// Get an iterator to the element following the last voxel.
428  typename std::vector<VoxelT>::const_iterator end() const
429  {
430  return _voxels.end();
431  }
432  /// Get an iterator to the element following the last voxel.
433  typename std::vector<VoxelT>::const_iterator cend() const
434  {
435  return _voxels.end();
436  }
437 
438 
439  /// Stream a human-readable description of the grid's structure.
440  template <class VoxelType>
441  friend std::ostream& operator<<(std::ostream& os, const VoxelGrid<VoxelType>& grid);
442 
443 
444  protected:
445 
446  /// The geometric structure.
448 
449  /// The voxel data.
450  std::vector<VoxelT> _voxels;
451 
452  };
453 
454 
455  template <typename VT>
457  {}
458 
459  template <typename VT>
461  VoxelGrid(structure, std::vector<VoxelT>(structure.getNumVoxels(), value))
462  {}
463 
464  template <typename VT>
466  const std::vector<VoxelGrid::VoxelT>& voxelData) :
467  _struct(structure)
468  {
469  if (voxelData.size() != structure.getNumVoxels())
470  {
471  throw error::InvalidVoxelDataSize(voxelData.size(), structure.getNumVoxels());
472  }
473  _voxels = voxelData;
474  }
475 
476  template <typename VT>
477  template <typename OtherVoxelT>
479  VoxelGrid(other.getStructure())
480  {}
481 
482 
483  template <typename VT>
484  std::ostream& operator<<(std::ostream& os, const VoxelGrid<VT>& grid)
485  {
486  os << "VoxelGrid " << grid._struct;
487  return os;
488  }
489 
490 }
visionx::voxelgrid::VoxelGrid::cbegin
std::vector< VoxelT >::const_iterator cbegin() const
Get an iterator to the first voxel.
Definition: VoxelGrid.hpp:417
exceptions.h
visionx::voxelgrid::VoxelGridStructure::getGridIndexMin
Eigen::Vector3i getGridIndexMin() const
Get the minimal (along each axis) grid index.
Definition: VoxelGridStructure.cpp:159
visionx::voxelgrid::VoxelGrid::setVoxels
void setVoxels(const std::vector< VoxelT > &voxels)
Set the voxels.
Definition: VoxelGrid.hpp:154
visionx::voxelgrid::VoxelGridStructure::getGridIndexMax
Eigen::Vector3i getGridIndexMax() const
Get the maximal (along each axis) grid index.
Definition: VoxelGridStructure.cpp:168
visionx::voxelgrid::VoxelGrid::setGridSizes
void setGridSizes(float gridSizes)
Set the grid size for a cubic grid. Resets the grid data.
Definition: VoxelGrid.hpp:182
visionx::voxelgrid::VoxelGrid::begin
std::vector< VoxelT >::iterator begin()
Get an iterator to the first voxel.
Definition: VoxelGrid.hpp:407
visionx::voxelgrid::VoxelGrid::getVoxel
const VoxelT & getVoxel(int x, int y, int z) const
Definition: VoxelGrid.hpp:118
visionx::voxelgrid::VoxelGrid::getVoxelFlatIndex
std::size_t getVoxelFlatIndex(int x, int y, int z) const
Get the flat index of the voxel with given grid index.
Definition: VoxelGrid.hpp:212
visionx::voxelgrid::VoxelGrid
A 3D grid of voxels of type _VoxelT.
Definition: VoxelGrid.hpp:50
visionx::voxelgrid::VoxelGrid::end
std::vector< VoxelT >::iterator end()
Get an iterator to the element following the last voxel.
Definition: VoxelGrid.hpp:423
visionx::voxelgrid::VoxelGrid::setCenterPose
void setCenterPose(const Eigen::Matrix4f &value)
Set the grid pose so that the grid center is the position of the given pose under the given orientati...
Definition: VoxelGrid.hpp:339
index
uint8_t index
Definition: EtherCATFrame.h:59
visionx::voxelgrid::VoxelGrid::reset
void reset(const VoxelT &value={})
Reset the voxel data by numVoxels() voxels with given value.
Definition: VoxelGrid.hpp:84
visionx::voxelgrid::VoxelGrid::VoxelGrid
VoxelGrid()
Construct a voxel grid with 0 voxels of size 1.0.
Definition: VoxelGrid.hpp:456
visionx::voxelgrid::VoxelGrid::getVoxelSizes
Eigen::Vector3f getVoxelSizes() const
Get the voxel size.
Definition: VoxelGrid.hpp:195
visionx::voxelgrid::VoxelGridStructure::getFlatIndex
std::size_t getFlatIndex(int x, int y, int z) const
Get the flat index for the given grid indices.
Definition: VoxelGridStructure.cpp:102
visionx::voxelgrid::VoxelGrid::_voxels
std::vector< VoxelT > _voxels
The voxel data.
Definition: VoxelGrid.hpp:450
visionx::voxelgrid::VoxelGridStructure::getVoxelSize
Eigen::Vector3f getVoxelSize() const
Get the voxel size.
Definition: VoxelGridStructure.cpp:82
visionx::voxelgrid::VoxelGridStructure::setGridSize
void setGridSize(int gridSize)
Set the grid size for a cubic grid.
Definition: VoxelGridStructure.cpp:72
visionx::voxelgrid::VoxelGrid::getPose
Eigen::Matrix4f getPose() const
Get the grid pose in the world frame.
Definition: VoxelGrid.hpp:320
visionx::voxelgrid::VoxelGridStructure::getOrientation
Eigen::Quaternionf getOrientation() const
Get the grid orienation in the world frame.
Definition: VoxelGridStructure.cpp:212
visionx::voxelgrid::VoxelGrid::setVoxelSizes
void setVoxelSizes(const Eigen::Vector3f &voxelSizes)
Set the voxel size. The grid data is not updated.
Definition: VoxelGrid.hpp:205
VoxelGridStructure.h
visionx::voxelgrid::VoxelGrid::operator[]
VoxelT & operator[](std::size_t index)
Get the voxel with given flat index.
Definition: VoxelGrid.hpp:386
visionx::voxelgrid::VoxelGrid::setGridSizes
void setGridSizes(const Eigen::Vector3i &gridSizes)
Set the grid size. This resets the grid data.
Definition: VoxelGrid.hpp:187
visionx::voxelgrid::VoxelGrid::resetStructure
void resetStructure(const VoxelGridStructure &structure)
Set the voxel grid structure and reset voxel data.
Definition: VoxelGrid.hpp:96
visionx::voxelgrid::VoxelGridStructure::setPose
void setPose(const Eigen::Matrix4f &pose)
Get the grid pose in the world frame.
Definition: VoxelGridStructure.cpp:237
visionx::voxelgrid::VoxelGrid< VoxelT >::VoxelT
VoxelT VoxelT
The voxel type.
Definition: VoxelGrid.hpp:55
visionx::voxelgrid::operator<<
std::ostream & operator<<(std::ostream &os, const VoxelGrid< VT > &grid)
Definition: VoxelGrid.hpp:484
visionx::voxelgrid::VoxelGrid::setOrientation
void setOrientation(const Eigen::Quaternionf &value)
Set the grid orienation in the world frame.
Definition: VoxelGrid.hpp:288
visionx::voxelgrid::VoxelGrid::getVoxelFlatIndex
std::size_t getVoxelFlatIndex(const Eigen::Vector3i &index) const
Get the flat index of the voxel with given grid index.
Definition: VoxelGrid.hpp:217
visionx::voxelgrid::VoxelGridStructure::getPose
Eigen::Matrix4f getPose() const
Get the grid pose in the world frame.
Definition: VoxelGridStructure.cpp:232
visionx::voxelgrid::VoxelGrid::setCenter
void setCenter(const Eigen::Vector3f &value)
Set the geometric center of the grid the world frame (which differs from the origin for even grid siz...
Definition: VoxelGrid.hpp:311
visionx::voxelgrid::VoxelGridStructure::getExtentOfCenters
Eigen::Vector3f getExtentOfCenters() const
Get extent of the grid along each axis (encompassing only voxel centers).
Definition: VoxelGridStructure.cpp:259
visionx::voxelgrid::error::InvalidVoxelDataSize
Indicates that voxel data with an invalid number of voxels has been passed to a VoxelGrid.
Definition: exceptions.h:29
visionx::voxelgrid::VoxelGrid::cend
std::vector< VoxelT >::const_iterator cend() const
Get an iterator to the element following the last voxel.
Definition: VoxelGrid.hpp:433
visionx::voxelgrid::VoxelGrid::getStructure
VoxelGridStructure getStructure() const
Get the voxel grid structure.
Definition: VoxelGrid.hpp:91
visionx::voxelgrid::VoxelGridStructure::getExtent
Eigen::Vector3f getExtent() const
Get extent of the grid along each axis (encompassing the whole voxels).
Definition: VoxelGridStructure.cpp:254
visionx::voxelgrid
Definition: exceptions.cpp:8
visionx::voxelgrid::VoxelGrid::getVoxel
VoxelT & getVoxel(int x, int y, int z)
Get the voxel with the given grid index.
Definition: VoxelGrid.hpp:114
visionx::voxelgrid::VoxelGrid::getVoxel
const VoxelT & getVoxel(std::size_t index) const
Definition: VoxelGrid.hpp:108
visionx::voxelgrid::VoxelGrid::operator[]
VoxelT & operator[](const Eigen::Vector3i &index)
Get the voxel with given grid index.
Definition: VoxelGrid.hpp:396
visionx::voxelgrid::VoxelGrid::getVoxel
VoxelT & getVoxel(std::size_t index)
Get the voxel with the given index.
Definition: VoxelGrid.hpp:104
visionx::voxelgrid::VoxelGridStructure::getLocalBoundingBoxOfCenters
Eigen::Matrix32f getLocalBoundingBoxOfCenters() const
Get the local axis aligned bounding box of the voxel centers (minimal/maximal values in columns).
Definition: VoxelGridStructure.cpp:272
visionx::voxelgrid::VoxelGrid::isInside
bool isInside(const Eigen::Vector3f &point, bool local=false) const
Indicate whether the given point is inside the voxel.
Definition: VoxelGrid.hpp:373
visionx::voxelgrid::VoxelGridStructure::isInside
bool isInside(const Eigen::Vector3i &indices) const
Indicate whether the given point is inside the voxel.
Definition: VoxelGridStructure.cpp:280
visionx::voxelgrid::VoxelGrid::numVoxels
std::size_t numVoxels() const
Get the number of voxels in the grid.
Definition: VoxelGrid.hpp:165
visionx::voxelgrid::VoxelGridStructure
Geometric structure of a 3D voxel grid.
Definition: VoxelGridStructure.h:96
visionx::voxelgrid::VoxelGrid::end
std::vector< VoxelT >::const_iterator end() const
Get an iterator to the element following the last voxel.
Definition: VoxelGrid.hpp:428
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:926
visionx::voxelgrid::VoxelGridStructure::getGridSize
Eigen::Vector3i getGridSize() const
Get the grid size.
Definition: VoxelGridStructure.cpp:67
visionx::voxelgrid::VoxelGrid::getVoxelCenter
Eigen::Vector3f getVoxelCenter(const Eigen::Vector3i &index, bool local=false) const
Get the center of the voxel with the given index.
Definition: VoxelGrid.hpp:261
visionx::voxelgrid::VoxelGrid::begin
std::vector< VoxelT >::const_iterator begin() const
Get an iterator to the first voxel.
Definition: VoxelGrid.hpp:412
visionx::voxelgrid::VoxelGridStructure::setCenter
void setCenter(const Eigen::Vector3f &center)
Set the geometric center of the grid the world frame (which differs from the origin for even grid siz...
Definition: VoxelGridStructure.cpp:227
visionx::voxelgrid::VoxelGridStructure::setOrigin
void setOrigin(const Eigen::Vector3f &value)
Set the grid origin the world frame (center of voxel [0 0 0]).
Definition: VoxelGridStructure.cpp:207
visionx::voxelgrid::VoxelGridStructure::setOrientation
void setOrientation(const Eigen::Quaternionf &value)
Set the grid orienation in the world frame.
Definition: VoxelGridStructure.cpp:217
visionx::voxelgrid::VoxelGridStructure::getCenterPose
Eigen::Matrix4f getCenterPose() const
Get the grid pose positioned at the grid center in the world frame.
Definition: VoxelGridStructure.cpp:243
visionx::voxelgrid::VoxelGrid::setOrigin
void setOrigin(const Eigen::Vector3f &value)
Set the grid origin the world frame (center of voxel [0 0 0]).
Definition: VoxelGrid.hpp:277
visionx::voxelgrid::VoxelGrid::getVoxelGridIndex
Eigen::Vector3i getVoxelGridIndex(size_t index) const
Get the grid index of the voxel with the given flat index.
Definition: VoxelGrid.hpp:228
visionx::voxelgrid::VoxelGrid::getVoxel
VoxelT & getVoxel(const Eigen::Vector3f &point, bool local=false)
Get the voxel closest to the given point.
Definition: VoxelGrid.hpp:135
visionx::voxelgrid::VoxelGrid::operator<<
friend std::ostream & operator<<(std::ostream &os, const VoxelGrid< VoxelType > &grid)
Stream a human-readable description of the grid's structure.
visionx::voxelgrid::VoxelGrid::getVoxelGridIndexMax
Eigen::Vector3i getVoxelGridIndexMax() const
Get the maximal (along each axis) voxel grid index.
Definition: VoxelGrid.hpp:245
visionx::voxelgrid::VoxelGrid::getOrientation
Eigen::Quaternionf getOrientation() const
Get the grid orienation in the world frame.
Definition: VoxelGrid.hpp:283
visionx::voxelgrid::VoxelGrid::getVoxelGridIndex
Eigen::Vector3i getVoxelGridIndex(const Eigen::Vector3f &point, bool local=false) const
Get the grid index of the voxel closest to point.
Definition: VoxelGrid.hpp:234
visionx::voxelgrid::VoxelGrid::getExtents
Eigen::Vector3f getExtents() const
Get extent of the grid along each axis (encompassing the whole voxels).
Definition: VoxelGrid.hpp:346
visionx::voxelgrid::VoxelGridStructure::getVoxelCenter
Eigen::Vector3f getVoxelCenter(std::size_t index, bool local=false) const
Get the center of the voxel with the given indices.
Definition: VoxelGridStructure.cpp:178
visionx::voxelgrid::VoxelGrid::getNumVoxels
std::size_t getNumVoxels() const
Get the number of voxels in the grid.
Definition: VoxelGrid.hpp:170
visionx::voxelgrid::VoxelGrid::getOrigin
Eigen::Vector3f getOrigin() const
Get the grid origin in the world frame (center of voxel [0 0 0]).
Definition: VoxelGrid.hpp:270
visionx::voxelgrid::VoxelGrid::getCenter
Eigen::Vector3f getCenter() const
Get the geometric center of the grid the world frame (which differs from the origin for even grid siz...
Definition: VoxelGrid.hpp:297
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
visionx::voxelgrid::VoxelGrid::operator[]
const VoxelT & operator[](std::size_t index) const
Definition: VoxelGrid.hpp:390
visionx::voxelgrid::VoxelGridStructure::getNumVoxels
std::size_t getNumVoxels() const
Get the number of voxels contained in the structure.
Definition: VoxelGridStructure.cpp:97
std
Definition: Application.h:66
armarx::Quaternion< float, 0 >
visionx::voxelgrid::VoxelGrid::getCenterPose
Eigen::Matrix4f getCenterPose() const
Get the grid pose positioned at the grid center in the world frame.
Definition: VoxelGrid.hpp:333
visionx::voxelgrid::VoxelGridStructure::setVoxelSize
void setVoxelSize(float voxelSize)
Set the voxel size for cubic voxels.
Definition: VoxelGridStructure.cpp:87
visionx::voxelgrid::VoxelGrid::getVoxel
const VoxelT & getVoxel(const Eigen::Vector3f &point, bool local=false) const
Definition: VoxelGrid.hpp:139
visionx::voxelgrid::VoxelGridStructure::checkIsInside
void checkIsInside(const Eigen::Vector3i &indices) const
Assert that the given indices are valid grid indices.
Definition: VoxelGridStructure.cpp:300
visionx::voxelgrid::VoxelGrid::setVoxelSizes
void setVoxelSizes(float voxelSize)
Set the voxel size of cubic voxels. The grid data is not updated.
Definition: VoxelGrid.hpp:200
visionx::voxelgrid::VoxelGrid::getVoxels
const std::vector< VoxelT > & getVoxels() const
Get the voxels.
Definition: VoxelGrid.hpp:147
visionx::voxelgrid::VoxelGrid::getGridSizes
Eigen::Vector3i getGridSizes() const
Get the grid size.
Definition: VoxelGrid.hpp:177
Eigen::Matrix
Definition: EigenForwardDeclarations.h:27
visionx::voxelgrid::VoxelGrid::getVoxelCenter
Eigen::Vector3f getVoxelCenter(std::size_t index, bool local=false) const
Get the center of the voxel with the given index.
Definition: VoxelGrid.hpp:251
visionx::voxelgrid::VoxelGridStructure::getCenter
Eigen::Vector3f getCenter() const
Get the geometric center of the grid the world frame (which differs from the origin for even grid siz...
Definition: VoxelGridStructure.cpp:222
visionx::voxelgrid::VoxelGrid::getVoxelCenter
Eigen::Vector3f getVoxelCenter(int x, int y, int z, bool local=false) const
Get the center of the voxel with the given index.
Definition: VoxelGrid.hpp:256
visionx::voxelgrid::VoxelGrid::isInside
bool isInside(const Eigen::Vector3i &index) const
Indicate whether the given point is inside the voxel.
Definition: VoxelGrid.hpp:368
visionx::voxelgrid::VoxelGrid::getVoxel
const VoxelT & getVoxel(const Eigen::Vector3i &index) const
Definition: VoxelGrid.hpp:128
visionx::voxelgrid::VoxelGrid::setPose
void setPose(const Eigen::Matrix4f &value)
Get the grid pose in the world frame.
Definition: VoxelGrid.hpp:327
visionx::VoxelGrid
voxelgrid::VoxelGrid< VoxelT > VoxelGrid
Definition: VoxelGridCore.h:33
visionx::voxelgrid::VoxelGrid::getLocalBoundingBox
Eigen::Matrix32f getLocalBoundingBox() const
Get the local axis aligned bounding box of the grid (minimal/maximal values in columns).
Definition: VoxelGrid.hpp:356
visionx::voxelgrid::VoxelGrid::getExtentsOfCenters
Eigen::Vector3f getExtentsOfCenters() const
Get extent of the grid along each axis (encompassing only voxel centers).
Definition: VoxelGrid.hpp:351
visionx::voxelgrid::VoxelGridStructure::getOrigin
Eigen::Vector3f getOrigin() const
Get the grid origin in the world frame (center of voxel [0 0 0]).
Definition: VoxelGridStructure.cpp:202
visionx::voxelgrid::VoxelGrid::getVoxel
VoxelT & getVoxel(const Eigen::Vector3i &index)
Get the voxel with the given grid index.
Definition: VoxelGrid.hpp:124
visionx::voxelgrid::VoxelGridStructure::getGridIndex
Eigen::Vector3i getGridIndex(size_t index) const
Get the voxel indices of the voxel with the given index.
Definition: VoxelGridStructure.cpp:127
visionx::voxelgrid::VoxelGrid::checkIsInside
void checkIsInside(const Eigen::Vector3i &index) const
Assert that the given index is a valid grid index.
Definition: VoxelGrid.hpp:379
visionx::voxelgrid::VoxelGridStructure::getLocalBoundingBox
Eigen::Matrix32f getLocalBoundingBox() const
Get the local axis aligned bounding box of the grid (minimal/maximal values in columns).
Definition: VoxelGridStructure.cpp:264
visionx::voxelgrid::VoxelGrid::getVoxelGridIndexMin
Eigen::Vector3i getVoxelGridIndexMin() const
Get the minimal (along each axis) voxel grid index.
Definition: VoxelGrid.hpp:240
visionx::voxelgrid::VoxelGrid::_struct
VoxelGridStructure _struct
The geometric structure.
Definition: VoxelGrid.hpp:447
visionx::voxelgrid::VoxelGrid::getLocalBoundingBoxOfCenters
Eigen::Matrix32f getLocalBoundingBoxOfCenters() const
Get the local axis aligned bounding box of the voxel centers (minimal/maximal values in columns).
Definition: VoxelGrid.hpp:361
visionx::voxelgrid::VoxelGrid::getVoxelFlatIndex
std::size_t getVoxelFlatIndex(const Eigen::Vector3f &point, bool local=false) const
Get the flat index of the voxel closest to point.
Definition: VoxelGrid.hpp:222
visionx::voxelgrid::VoxelGridStructure::setCenterPose
void setCenterPose(const Eigen::Matrix4f &pose)
Set the grid pose so that the grid center is the position of the given pose under the given orientati...
Definition: VoxelGridStructure.cpp:248
visionx::voxelgrid::VoxelGrid::operator[]
const VoxelT & operator[](const Eigen::Vector3i &index) const
Definition: VoxelGrid.hpp:400