VoxelGrid< _VoxelT > Class Template Reference

A 3D grid of voxels of type _VoxelT. More...

#include <VisionX/libraries/VoxelGridCore/VoxelGrid.hpp>

Public Types

using VoxelT = _VoxelT
 The voxel type.
 

Public Member Functions

std::vector< VoxelT >::iterator begin ()
 Get an iterator to the first voxel.
 
std::vector< VoxelT >::const_iterator begin () const
 Get an iterator to the first voxel.
 
std::vector< VoxelT >::const_iterator cbegin () const
 Get an iterator to the first voxel.
 
std::vector< VoxelT >::const_iterator cend () const
 Get an iterator to the element following the last voxel.
 
void checkIsInside (const Eigen::Vector3i &index) const
 Assert that the given index is a valid grid index.
 
std::vector< VoxelT >::iterator end ()
 Get an iterator to the element following the last voxel.
 
std::vector< VoxelT >::const_iterator end () const
 Get an iterator to the element following the last voxel.
 
Eigen::Vector3f getCenter () const
 Get the geometric center of the grid the world frame (which differs from the origin for even grid sizes).
 
Eigen::Matrix4f getCenterPose () const
 Get the grid pose positioned at the grid center in the world frame.
 
Eigen::Vector3f getExtents () const
 Get extent of the grid along each axis (encompassing the whole voxels).
 
Eigen::Vector3f getExtentsOfCenters () const
 Get extent of the grid along each axis (encompassing only voxel centers).
 
Eigen::Vector3i getGridSizes () const
 Get the grid size.
 
Eigen::Matrix32f getLocalBoundingBox () const
 Get the local axis aligned bounding box of the grid (minimal/maximal values in columns).
 
Eigen::Matrix32f getLocalBoundingBoxOfCenters () const
 Get the local axis aligned bounding box of the voxel centers (minimal/maximal values in columns).
 
std::size_t getNumVoxels () const
 Get the number of voxels in the grid.
 
Eigen::Quaternionf getOrientation () const
 Get the grid orienation in the world frame.
 
Eigen::Vector3f getOrigin () const
 Get the grid origin in the world frame (center of voxel [0 0 0]).
 
Eigen::Matrix4f getPose () const
 Get the grid pose in the world frame.
 
VoxelGridStructure getStructure () const
 Get the voxel grid structure.
 
VoxelTgetVoxel (const Eigen::Vector3f &point, bool local=false)
 Get the voxel closest to the given point.
 
const VoxelTgetVoxel (const Eigen::Vector3f &point, bool local=false) const
 
VoxelTgetVoxel (const Eigen::Vector3i &index)
 Get the voxel with the given grid index.
 
const VoxelTgetVoxel (const Eigen::Vector3i &index) const
 
VoxelTgetVoxel (int x, int y, int z)
 Get the voxel with the given grid index.
 
const VoxelTgetVoxel (int x, int y, int z) const
 
VoxelTgetVoxel (std::size_t index)
 Get the voxel with the given index.
 
const VoxelTgetVoxel (std::size_t index) const
 
Eigen::Vector3f getVoxelCenter (const Eigen::Vector3i &index, bool local=false) const
 Get the center of the voxel with the given index.
 
Eigen::Vector3f getVoxelCenter (int x, int y, int z, bool local=false) const
 Get the center of the voxel with the given index.
 
Eigen::Vector3f getVoxelCenter (std::size_t index, bool local=false) const
 Get the center of the voxel with the given index.
 
std::size_t getVoxelFlatIndex (const Eigen::Vector3f &point, bool local=false) const
 Get the flat index of the voxel closest to point.
 
std::size_t getVoxelFlatIndex (const Eigen::Vector3i &index) const
 Get the flat index of the voxel with given grid index.
 
std::size_t getVoxelFlatIndex (int x, int y, int z) const
 Get the flat index of the voxel with given grid index.
 
Eigen::Vector3i getVoxelGridIndex (const Eigen::Vector3f &point, bool local=false) const
 Get the grid index of the voxel closest to point.
 
Eigen::Vector3i getVoxelGridIndex (size_t index) const
 Get the grid index of the voxel with the given flat index.
 
Eigen::Vector3i getVoxelGridIndexMax () const
 Get the maximal (along each axis) voxel grid index.
 
Eigen::Vector3i getVoxelGridIndexMin () const
 Get the minimal (along each axis) voxel grid index.
 
const std::vector< VoxelT > & getVoxels () const
 Get the voxels.
 
Eigen::Vector3f getVoxelSizes () const
 Get the voxel size.
 
bool isInside (const Eigen::Vector3f &point, bool local=false) const
 Indicate whether the given point is inside the voxel.
 
bool isInside (const Eigen::Vector3i &index) const
 Indicate whether the given point is inside the voxel.
 
std::size_t numVoxels () const
 Get the number of voxels in the grid.
 
VoxelToperator[] (const Eigen::Vector3i &index)
 Get the voxel with given grid index.
 
const VoxelToperator[] (const Eigen::Vector3i &index) const
 
VoxelToperator[] (std::size_t index)
 Get the voxel with given flat index.
 
const VoxelToperator[] (std::size_t index) const
 
void reset (const VoxelT &value={})
 Reset the voxel data by numVoxels() voxels with given value.
 
void resetStructure (const VoxelGridStructure &structure)
 Set the voxel grid structure and reset voxel data.
 
void setCenter (const Eigen::Vector3f &value)
 Set the geometric center of the grid the world frame (which differs from the origin for even grid sizes).
 
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 orientation.
 
void setGridSizes (const Eigen::Vector3i &gridSizes)
 Set the grid size. This resets the grid data.
 
void setGridSizes (float gridSizes)
 Set the grid size for a cubic grid. Resets the grid data.
 
void setOrientation (const Eigen::Quaternionf &value)
 Set the grid orienation in the world frame.
 
void setOrigin (const Eigen::Vector3f &value)
 Set the grid origin the world frame (center of voxel [0 0 0]).
 
void setPose (const Eigen::Matrix4f &value)
 Get the grid pose in the world frame.
 
void setVoxels (const std::vector< VoxelT > &voxels)
 Set the voxels.
 
void setVoxelSizes (const Eigen::Vector3f &voxelSizes)
 Set the voxel size. The grid data is not updated.
 
void setVoxelSizes (float voxelSize)
 Set the voxel size of cubic voxels. The grid data is not updated.
 
 VoxelGrid ()
 Construct a voxel grid with 0 voxels of size 1.0.
 
template<typename OtherVoxelT>
 VoxelGrid (const VoxelGrid< OtherVoxelT > &other)
 Construct a voxel grid with the same structure as other.
 
 VoxelGrid (const VoxelGrid< VoxelT > &other)=default
 Ordinary copy constructor for voxel grid with same VoxelT.
 
 VoxelGrid (const VoxelGridStructure &structure, const std::vector< VoxelGrid::VoxelT > &voxelData)
 Construct a voxel grid with the given structure and data.
 
 VoxelGrid (const VoxelGridStructure &structure, const VoxelT &value={})
 Construct a voxel grid with the given structure and voxels with given value.
 

Protected Attributes

VoxelGridStructure _struct
 The geometric structure.
 
std::vector< VoxelT_voxels
 The voxel data.
 

Friends

template<class VoxelType>
std::ostream & operator<< (std::ostream &os, const VoxelGrid< VoxelType > &grid)
 Stream a human-readable description of the grid's structure.
 

Detailed Description

template<typename _VoxelT>
class visionx::voxelgrid::VoxelGrid< _VoxelT >

A 3D grid of voxels of type _VoxelT.

A VoxelGrid three-dimensional regular grid of cuboids, called voxels. Its geometric structure is defined by a VoxelGridStructure. In addition, it stores voxel data of type _VoxelT (one per voxel).

This is a generic implementation made to hold hold arbitrary data. As such, there is no concept of "free/occupied" voxels".

See also
VoxelGridStructure

Definition at line 49 of file VoxelGrid.hpp.

Member Typedef Documentation

◆ VoxelT

template<typename _VoxelT>
using VoxelT = _VoxelT

The voxel type.

Definition at line 53 of file VoxelGrid.hpp.

Constructor & Destructor Documentation

◆ VoxelGrid() [1/5]

template<typename VT>
VoxelGrid ( )

Construct a voxel grid with 0 voxels of size 1.0.

Definition at line 524 of file VoxelGrid.hpp.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ VoxelGrid() [2/5]

template<typename VT>
VoxelGrid ( const VoxelGridStructure & structure,
const VoxelT & value = {} )

Construct a voxel grid with the given structure and voxels with given value.

Definition at line 529 of file VoxelGrid.hpp.

+ Here is the call graph for this function:

◆ VoxelGrid() [3/5]

template<typename VT>
VoxelGrid ( const VoxelGridStructure & structure,
const std::vector< VoxelGrid< _VoxelT >::VoxelT > & voxelData )

Construct a voxel grid with the given structure and data.

The size of voxelData must match the grid size of structure.

Exceptions
error::InvalidVoxelDataSizeIf the size does not match.

Definition at line 535 of file VoxelGrid.hpp.

+ Here is the call graph for this function:

◆ VoxelGrid() [4/5]

template<typename VT>
template<typename OtherVoxelT>
VoxelGrid ( const VoxelGrid< OtherVoxelT > & other)

Construct a voxel grid with the same structure as other.

Definition at line 548 of file VoxelGrid.hpp.

+ Here is the call graph for this function:

◆ VoxelGrid() [5/5]

template<typename _VoxelT>
VoxelGrid ( const VoxelGrid< VoxelT > & other)
default

Ordinary copy constructor for voxel grid with same VoxelT.

Member Function Documentation

◆ begin() [1/2]

template<typename _VoxelT>
std::vector< VoxelT >::iterator begin ( )
inline

Get an iterator to the first voxel.

Definition at line 469 of file VoxelGrid.hpp.

◆ begin() [2/2]

template<typename _VoxelT>
std::vector< VoxelT >::const_iterator begin ( ) const
inline

Get an iterator to the first voxel.

Definition at line 476 of file VoxelGrid.hpp.

◆ cbegin()

template<typename _VoxelT>
std::vector< VoxelT >::const_iterator cbegin ( ) const
inline

Get an iterator to the first voxel.

Definition at line 483 of file VoxelGrid.hpp.

◆ cend()

template<typename _VoxelT>
std::vector< VoxelT >::const_iterator cend ( ) const
inline

Get an iterator to the element following the last voxel.

Definition at line 504 of file VoxelGrid.hpp.

◆ checkIsInside()

template<typename _VoxelT>
void checkIsInside ( const Eigen::Vector3i & index) const
inline

Assert that the given index is a valid grid index.

Definition at line 436 of file VoxelGrid.hpp.

◆ end() [1/2]

template<typename _VoxelT>
std::vector< VoxelT >::iterator end ( )
inline

Get an iterator to the element following the last voxel.

Definition at line 490 of file VoxelGrid.hpp.

◆ end() [2/2]

template<typename _VoxelT>
std::vector< VoxelT >::const_iterator end ( ) const
inline

Get an iterator to the element following the last voxel.

Definition at line 497 of file VoxelGrid.hpp.

◆ getCenter()

template<typename _VoxelT>
Eigen::Vector3f getCenter ( ) const
inline

Get the geometric center of the grid the world frame (which differs from the origin for even grid sizes).

Definition at line 338 of file VoxelGrid.hpp.

◆ getCenterPose()

template<typename _VoxelT>
Eigen::Matrix4f getCenterPose ( ) const
inline

Get the grid pose positioned at the grid center in the world frame.

Definition at line 379 of file VoxelGrid.hpp.

◆ getExtents()

template<typename _VoxelT>
Eigen::Vector3f getExtents ( ) const
inline

Get extent of the grid along each axis (encompassing the whole voxels).

Definition at line 394 of file VoxelGrid.hpp.

◆ getExtentsOfCenters()

template<typename _VoxelT>
Eigen::Vector3f getExtentsOfCenters ( ) const
inline

Get extent of the grid along each axis (encompassing only voxel centers).

Definition at line 401 of file VoxelGrid.hpp.

◆ getGridSizes()

template<typename _VoxelT>
Eigen::Vector3i getGridSizes ( ) const
inline

Get the grid size.

Definition at line 189 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ getLocalBoundingBox()

template<typename _VoxelT>
Eigen::Matrix32f getLocalBoundingBox ( ) const
inline

Get the local axis aligned bounding box of the grid (minimal/maximal values in columns).

Definition at line 408 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ getLocalBoundingBoxOfCenters()

template<typename _VoxelT>
Eigen::Matrix32f getLocalBoundingBoxOfCenters ( ) const
inline

Get the local axis aligned bounding box of the voxel centers (minimal/maximal values in columns).

Definition at line 415 of file VoxelGrid.hpp.

◆ getNumVoxels()

template<typename _VoxelT>
std::size_t getNumVoxels ( ) const
inline

Get the number of voxels in the grid.

Definition at line 182 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ getOrientation()

template<typename _VoxelT>
Eigen::Quaternionf getOrientation ( ) const
inline

Get the grid orienation in the world frame.

Definition at line 321 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ getOrigin()

template<typename _VoxelT>
Eigen::Vector3f getOrigin ( ) const
inline

Get the grid origin in the world frame (center of voxel [0 0 0]).

Note that this differs from the geometric center for even grid sizes.

See also
getCenter()

Definition at line 305 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ getPose()

template<typename _VoxelT>
Eigen::Matrix4f getPose ( ) const
inline

Get the grid pose in the world frame.

Note that this differs from the geometric center for even grid sizes.

See also
getCenterPose()

Definition at line 363 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ getStructure()

template<typename _VoxelT>
VoxelGridStructure getStructure ( ) const
inline

Get the voxel grid structure.

Definition at line 87 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ getVoxel() [1/8]

template<typename _VoxelT>
VoxelT & getVoxel ( const Eigen::Vector3f & point,
bool local = false )
inline

Get the voxel closest to the given point.

Parameters
localIf false (default), the point is transformed to local coordinate system.

Definition at line 142 of file VoxelGrid.hpp.

◆ getVoxel() [2/8]

template<typename _VoxelT>
const VoxelT & getVoxel ( const Eigen::Vector3f & point,
bool local = false ) const
inline

Definition at line 148 of file VoxelGrid.hpp.

◆ getVoxel() [3/8]

template<typename _VoxelT>
VoxelT & getVoxel ( const Eigen::Vector3i & index)
inline

Get the voxel with the given grid index.

See also
operator[]

Definition at line 128 of file VoxelGrid.hpp.

◆ getVoxel() [4/8]

template<typename _VoxelT>
const VoxelT & getVoxel ( const Eigen::Vector3i & index) const
inline

Definition at line 134 of file VoxelGrid.hpp.

◆ getVoxel() [5/8]

template<typename _VoxelT>
VoxelT & getVoxel ( int x,
int y,
int z )
inline

Get the voxel with the given grid index.

See also
operator[]

Definition at line 115 of file VoxelGrid.hpp.

◆ getVoxel() [6/8]

template<typename _VoxelT>
const VoxelT & getVoxel ( int x,
int y,
int z ) const
inline

Definition at line 121 of file VoxelGrid.hpp.

◆ getVoxel() [7/8]

template<typename _VoxelT>
VoxelT & getVoxel ( std::size_t index)
inline

Get the voxel with the given index.

See also
operator[]

Definition at line 102 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ getVoxel() [8/8]

template<typename _VoxelT>
const VoxelT & getVoxel ( std::size_t index) const
inline

Definition at line 108 of file VoxelGrid.hpp.

◆ getVoxelCenter() [1/3]

template<typename _VoxelT>
Eigen::Vector3f getVoxelCenter ( const Eigen::Vector3i & index,
bool local = false ) const
inline

Get the center of the voxel with the given index.

Definition at line 296 of file VoxelGrid.hpp.

◆ getVoxelCenter() [2/3]

template<typename _VoxelT>
Eigen::Vector3f getVoxelCenter ( int x,
int y,
int z,
bool local = false ) const
inline

Get the center of the voxel with the given index.

Definition at line 289 of file VoxelGrid.hpp.

◆ getVoxelCenter() [3/3]

template<typename _VoxelT>
Eigen::Vector3f getVoxelCenter ( std::size_t index,
bool local = false ) const
inline

Get the center of the voxel with the given index.

Definition at line 282 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ getVoxelFlatIndex() [1/3]

template<typename _VoxelT>
std::size_t getVoxelFlatIndex ( const Eigen::Vector3f & point,
bool local = false ) const
inline

Get the flat index of the voxel closest to point.

Definition at line 246 of file VoxelGrid.hpp.

◆ getVoxelFlatIndex() [2/3]

template<typename _VoxelT>
std::size_t getVoxelFlatIndex ( const Eigen::Vector3i & index) const
inline

Get the flat index of the voxel with given grid index.

Definition at line 239 of file VoxelGrid.hpp.

◆ getVoxelFlatIndex() [3/3]

template<typename _VoxelT>
std::size_t getVoxelFlatIndex ( int x,
int y,
int z ) const
inline

Get the flat index of the voxel with given grid index.

Definition at line 232 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ getVoxelGridIndex() [1/2]

template<typename _VoxelT>
Eigen::Vector3i getVoxelGridIndex ( const Eigen::Vector3f & point,
bool local = false ) const
inline

Get the grid index of the voxel closest to point.

Parameters
localIf false (default), the point is transformed to local coordinate system.

Definition at line 261 of file VoxelGrid.hpp.

◆ getVoxelGridIndex() [2/2]

template<typename _VoxelT>
Eigen::Vector3i getVoxelGridIndex ( size_t index) const
inline

Get the grid index of the voxel with the given flat index.

Definition at line 253 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ getVoxelGridIndexMax()

template<typename _VoxelT>
Eigen::Vector3i getVoxelGridIndexMax ( ) const
inline

Get the maximal (along each axis) voxel grid index.

Definition at line 275 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ getVoxelGridIndexMin()

template<typename _VoxelT>
Eigen::Vector3i getVoxelGridIndexMin ( ) const
inline

Get the minimal (along each axis) voxel grid index.

Definition at line 268 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ getVoxels()

template<typename _VoxelT>
const std::vector< VoxelT > & getVoxels ( ) const
inline

Get the voxels.

Note
VoxelGrid provides begin()/end() pairs, so it can be iterated over directly.

Definition at line 156 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ getVoxelSizes()

template<typename _VoxelT>
Eigen::Vector3f getVoxelSizes ( ) const
inline

Get the voxel size.

Definition at line 211 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ isInside() [1/2]

template<typename _VoxelT>
bool isInside ( const Eigen::Vector3f & point,
bool local = false ) const
inline

Indicate whether the given point is inside the voxel.

Definition at line 429 of file VoxelGrid.hpp.

◆ isInside() [2/2]

template<typename _VoxelT>
bool isInside ( const Eigen::Vector3i & index) const
inline

Indicate whether the given point is inside the voxel.

Definition at line 422 of file VoxelGrid.hpp.

◆ numVoxels()

template<typename _VoxelT>
std::size_t numVoxels ( ) const
inline

Get the number of voxels in the grid.

Definition at line 175 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ operator[]() [1/4]

template<typename _VoxelT>
VoxelT & operator[] ( const Eigen::Vector3i & index)
inline

Get the voxel with given grid index.

See also
getVoxel(const Eigen::Vector3i&)

Definition at line 456 of file VoxelGrid.hpp.

◆ operator[]() [2/4]

template<typename _VoxelT>
const VoxelT & operator[] ( const Eigen::Vector3i & index) const
inline

Definition at line 462 of file VoxelGrid.hpp.

◆ operator[]() [3/4]

template<typename _VoxelT>
VoxelT & operator[] ( std::size_t index)
inline

Get the voxel with given flat index.

See also
getVoxel(std::size_t)

Definition at line 443 of file VoxelGrid.hpp.

◆ operator[]() [4/4]

template<typename _VoxelT>
const VoxelT & operator[] ( std::size_t index) const
inline

Definition at line 449 of file VoxelGrid.hpp.

◆ reset()

template<typename _VoxelT>
void reset ( const VoxelT & value = {})
inline

Reset the voxel data by numVoxels() voxels with given value.

Definition at line 80 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ resetStructure()

template<typename _VoxelT>
void resetStructure ( const VoxelGridStructure & structure)
inline

Set the voxel grid structure and reset voxel data.

Definition at line 94 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ setCenter()

template<typename _VoxelT>
void setCenter ( const Eigen::Vector3f & value)
inline

Set the geometric center of the grid the world frame (which differs from the origin for even grid sizes).

Note
This computes the origin from the given center using the current orientation. If you want to set grid center and orientation, set the orientation first, or (equivalently), use setCenterPose().
See also
setPoseGridCenter()

Definition at line 354 of file VoxelGrid.hpp.

◆ setCenterPose()

template<typename _VoxelT>
void setCenterPose ( const Eigen::Matrix4f & value)
inline

Set the grid pose so that the grid center is the position of the given pose under the given orientation.

Definition at line 387 of file VoxelGrid.hpp.

◆ setGridSizes() [1/2]

template<typename _VoxelT>
void setGridSizes ( const Eigen::Vector3i & gridSizes)
inline

Set the grid size. This resets the grid data.

Definition at line 203 of file VoxelGrid.hpp.

◆ setGridSizes() [2/2]

template<typename _VoxelT>
void setGridSizes ( float gridSizes)
inline

Set the grid size for a cubic grid. Resets the grid data.

Definition at line 196 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ setOrientation()

template<typename _VoxelT>
void setOrientation ( const Eigen::Quaternionf & value)
inline

Set the grid orienation in the world frame.

Definition at line 328 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ setOrigin()

template<typename _VoxelT>
void setOrigin ( const Eigen::Vector3f & value)
inline

Set the grid origin the world frame (center of voxel [0 0 0]).

Note that this differs from the geometric center for even grid sizes.

See also
setCenter()

Definition at line 314 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ setPose()

template<typename _VoxelT>
void setPose ( const Eigen::Matrix4f & value)
inline

Get the grid pose in the world frame.

Note that this differs from the geometric center for even grid sizes.

See also
setCenterPose()

Definition at line 372 of file VoxelGrid.hpp.

◆ setVoxels()

template<typename _VoxelT>
void setVoxels ( const std::vector< VoxelT > & voxels)
inline

Set the voxels.

(Size must match numVoxels()).

Exceptions
error::InvalidVoxelDataSizeIf the size does not match.

Definition at line 164 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

◆ setVoxelSizes() [1/2]

template<typename _VoxelT>
void setVoxelSizes ( const Eigen::Vector3f & voxelSizes)
inline

Set the voxel size. The grid data is not updated.

Definition at line 225 of file VoxelGrid.hpp.

◆ setVoxelSizes() [2/2]

template<typename _VoxelT>
void setVoxelSizes ( float voxelSize)
inline

Set the voxel size of cubic voxels. The grid data is not updated.

Definition at line 218 of file VoxelGrid.hpp.

+ Here is the caller graph for this function:

Friends And Related Symbol Documentation

◆ operator<<

template<typename _VoxelT>
template<class VoxelType>
std::ostream & operator<< ( std::ostream & os,
const VoxelGrid< VoxelType > & grid )
friend

Stream a human-readable description of the grid's structure.

Member Data Documentation

◆ _struct

template<typename _VoxelT>
VoxelGridStructure _struct
protected

The geometric structure.

Definition at line 517 of file VoxelGrid.hpp.

◆ _voxels

template<typename _VoxelT>
std::vector<VoxelT> _voxels
protected

The voxel data.

Definition at line 520 of file VoxelGrid.hpp.


The documentation for this class was generated from the following file: