Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
lvr2::HashGrid< BaseVecT, BoxT > Class Template Reference

#include <HashGrid.hpp>

Inheritance diagram for lvr2::HashGrid< BaseVecT, BoxT >:
Inheritance graph
[legend]

Public Types

typedef unordered_map< size_t, BoxT * > box_map
 Typedef to alias box map. More...
 
typedef unordered_map< size_t, BoxT * >::iterator box_map_it
 Typedef to alias iterators for box maps. More...
 
typedef unordered_map< size_t, size_t > qp_map
 
typedef vector< QueryPoint< BaseVecT > >::iterator query_point_it
 Typedef to alias iterators to query points. More...
 

Public Member Functions

virtual void addLatticePoint (int i, int j, int k, float distance=0.0)
 
void calcIndices ()
 Calculates needed lattice parameters. More...
 
unsigned int findQueryPoint (int position, int x, int y, int z)
 Searches for a existing shared lattice point in the grid. More...
 
box_map_it firstCell ()
 
query_point_it firstQueryPoint ()
 
BoundingBox< BaseVecT > & getBoundingBox ()
 
box_map getCells ()
 
size_t getMaxIndex ()
 
size_t getMaxIndexX ()
 
size_t getMaxIndexY ()
 
size_t getMaxIndexZ ()
 
size_t getNumberOfCells ()
 
vector< QueryPoint< BaseVecT > > & getQueryPoints ()
 
 HashGrid (float cellSize, BoundingBox< BaseVecT > boundingBox, bool isVoxelSize=true, bool extrude=true)
 
 HashGrid (std::vector< PointBufferPtr > chunks, std::vector< BoundingBox< BaseVecT >> innerBoxes, BoundingBox< BaseVecT > &boundingBox, float voxelSize)
 
 HashGrid (std::vector< string > &files, BoundingBox< BaseVecT > &boundingBox, float voxelsize)
 
 HashGrid (std::vector< string > &files, std::vector< BoundingBox< BaseVecT >> innerBoxes, BoundingBox< BaseVecT > &boundingBox, float voxelsize)
 
 HashGrid (string file)
 
size_t hashValue (int i, int j, int k) const
 Calculates the hash value for the given index triple. More...
 
box_map_it lastCell ()
 
query_point_it lastQueryPoint ()
 
void saveCells (string file)
 Saves a representation of the cells to the given file. More...
 
virtual void saveGrid (string file)
 Saves a representation of the grid to the given file. More...
 
virtual void serialize (string file)
 
void setBB (BoundingBox< BaseVecT > &bb)
 
void setCoordinateScaling (float x, float y, float z)
 Set x, y, z values to scale the scene or use combinations of +/-1 to mapp different coordinate systems. More...
 
virtual ~HashGrid ()
 
- Public Member Functions inherited from lvr2::GridBase
 GridBase (bool extrude=true)
 
virtual void setExtrusion (bool extrude)
 
virtual ~GridBase ()
 

Public Attributes

BoundingBox< BaseVecT > qp_bb
 

Protected Member Functions

int calcIndex (float f)
 

Protected Attributes

BoundingBox< BaseVecT > m_boundingBox
 Bounding box of the covered volume. More...
 
string m_boxType
 True if a local tetraeder decomposition is used for reconstruction. More...
 
box_map m_cells
 Map to handle the boxes in the grid. More...
 
BaseVecT m_coordinateScales
 Save scaling factors (i.e., -1 or +1) to mapp different coordinate systems. More...
 
unsigned int m_globalIndex
 The maximum used cell index within the grid. More...
 
size_t m_maxIndex
 The absolute maximal index of the reconstruction grid. More...
 
size_t m_maxIndexSquare
 The squared maximal index of the reconstruction grid. More...
 
size_t m_maxIndexX
 The maximal index in x direction. More...
 
size_t m_maxIndexY
 The maximal index in y direction. More...
 
size_t m_maxIndexZ
 The maximal index in z direction. More...
 
qp_map m_qpIndices
 
vector< QueryPoint< BaseVecT > > m_queryPoints
 A vector containing the query points for the reconstruction. More...
 
float m_voxelsize
 The voxelsize used for reconstruction. More...
 
- Protected Attributes inherited from lvr2::GridBase
bool m_extrude
 

Detailed Description

template<typename BaseVecT, typename BoxT>
class lvr2::HashGrid< BaseVecT, BoxT >

Definition at line 94 of file HashGrid.hpp.

Member Typedef Documentation

◆ box_map

template<typename BaseVecT , typename BoxT >
typedef unordered_map<size_t, BoxT*> lvr2::HashGrid< BaseVecT, BoxT >::box_map

Typedef to alias box map.

Definition at line 101 of file HashGrid.hpp.

◆ box_map_it

template<typename BaseVecT , typename BoxT >
typedef unordered_map<size_t, BoxT*>::iterator lvr2::HashGrid< BaseVecT, BoxT >::box_map_it

Typedef to alias iterators for box maps.

Definition at line 106 of file HashGrid.hpp.

◆ qp_map

template<typename BaseVecT , typename BoxT >
typedef unordered_map<size_t, size_t> lvr2::HashGrid< BaseVecT, BoxT >::qp_map

Definition at line 103 of file HashGrid.hpp.

◆ query_point_it

template<typename BaseVecT , typename BoxT >
typedef vector<QueryPoint<BaseVecT> >::iterator lvr2::HashGrid< BaseVecT, BoxT >::query_point_it

Typedef to alias iterators to query points.

Definition at line 109 of file HashGrid.hpp.

Constructor & Destructor Documentation

◆ HashGrid() [1/5]

template<typename BaseVecT , typename BoxT >
lvr2::HashGrid< BaseVecT, BoxT >::HashGrid ( float  cellSize,
BoundingBox< BaseVecT >  boundingBox,
bool  isVoxelSize = true,
bool  extrude = true 
)

◆ HashGrid() [2/5]

template<typename BaseVecT , typename BoxT >
lvr2::HashGrid< BaseVecT, BoxT >::HashGrid ( string  file)

◆ HashGrid() [3/5]

template<typename BaseVecT , typename BoxT >
lvr2::HashGrid< BaseVecT, BoxT >::HashGrid ( std::vector< string > &  files,
BoundingBox< BaseVecT > &  boundingBox,
float  voxelsize 
)

◆ HashGrid() [4/5]

template<typename BaseVecT , typename BoxT >
lvr2::HashGrid< BaseVecT, BoxT >::HashGrid ( std::vector< string > &  files,
std::vector< BoundingBox< BaseVecT >>  innerBoxes,
BoundingBox< BaseVecT > &  boundingBox,
float  voxelsize 
)

◆ HashGrid() [5/5]

template<typename BaseVecT , typename BoxT >
lvr2::HashGrid< BaseVecT, BoxT >::HashGrid ( std::vector< PointBufferPtr chunks,
std::vector< BoundingBox< BaseVecT >>  innerBoxes,
BoundingBox< BaseVecT > &  boundingBox,
float  voxelSize 
)

◆ ~HashGrid()

template<typename BaseVecT , typename BoxT >
virtual lvr2::HashGrid< BaseVecT, BoxT >::~HashGrid ( )
virtual

Member Function Documentation

◆ addLatticePoint()

template<typename BaseVecT , typename BoxT >
virtual void lvr2::HashGrid< BaseVecT, BoxT >::addLatticePoint ( int  i,
int  j,
int  k,
float  distance = 0.0 
)
virtual
Parameters
iDiscrete x position within the grid.
jDiscrete y position within the grid.
kDiscrete z position within the grid.
distanceSigned distance to the represented surface at the position within the grid.

Implements lvr2::GridBase.

◆ calcIndex()

template<typename BaseVecT , typename BoxT >
int lvr2::HashGrid< BaseVecT, BoxT >::calcIndex ( float  f)
inlineprotected

Definition at line 281 of file HashGrid.hpp.

◆ calcIndices()

template<typename BaseVecT , typename BoxT >
void lvr2::HashGrid< BaseVecT, BoxT >::calcIndices ( )

Calculates needed lattice parameters.

◆ findQueryPoint()

template<typename BaseVecT , typename BoxT >
unsigned int lvr2::HashGrid< BaseVecT, BoxT >::findQueryPoint ( int  position,
int  x,
int  y,
int  z 
)

Searches for a existing shared lattice point in the grid.

Parameters
positionNumber of a possible neighbor
xx index within the grid
yy index within the grid
zz index within the grid
Returns
Query point index of the found point, INVALID_INDEX otherwise

◆ firstCell()

template<typename BaseVecT , typename BoxT >
box_map_it lvr2::HashGrid< BaseVecT, BoxT >::firstCell ( )
inline
Returns
Returns an iterator to the first box in the cell map.

Definition at line 205 of file HashGrid.hpp.

◆ firstQueryPoint()

template<typename BaseVecT , typename BoxT >
query_point_it lvr2::HashGrid< BaseVecT, BoxT >::firstQueryPoint ( )
inline
Returns
Returns an iterator to the first query point

Definition at line 215 of file HashGrid.hpp.

◆ getBoundingBox()

template<typename BaseVecT , typename BoxT >
BoundingBox<BaseVecT>& lvr2::HashGrid< BaseVecT, BoxT >::getBoundingBox ( )
inline

Definition at line 247 of file HashGrid.hpp.

◆ getCells()

template<typename BaseVecT , typename BoxT >
box_map lvr2::HashGrid< BaseVecT, BoxT >::getCells ( )
inline

Definition at line 224 of file HashGrid.hpp.

◆ getMaxIndex()

template<typename BaseVecT , typename BoxT >
size_t lvr2::HashGrid< BaseVecT, BoxT >::getMaxIndex ( )
inline

Definition at line 237 of file HashGrid.hpp.

◆ getMaxIndexX()

template<typename BaseVecT , typename BoxT >
size_t lvr2::HashGrid< BaseVecT, BoxT >::getMaxIndexX ( )
inline

Definition at line 239 of file HashGrid.hpp.

◆ getMaxIndexY()

template<typename BaseVecT , typename BoxT >
size_t lvr2::HashGrid< BaseVecT, BoxT >::getMaxIndexY ( )
inline

Definition at line 241 of file HashGrid.hpp.

◆ getMaxIndexZ()

template<typename BaseVecT , typename BoxT >
size_t lvr2::HashGrid< BaseVecT, BoxT >::getMaxIndexZ ( )
inline

Definition at line 243 of file HashGrid.hpp.

◆ getNumberOfCells()

template<typename BaseVecT , typename BoxT >
size_t lvr2::HashGrid< BaseVecT, BoxT >::getNumberOfCells ( )
inline

Definition at line 200 of file HashGrid.hpp.

◆ getQueryPoints()

template<typename BaseVecT , typename BoxT >
vector<QueryPoint<BaseVecT> >& lvr2::HashGrid< BaseVecT, BoxT >::getQueryPoints ( )
inline

Definition at line 222 of file HashGrid.hpp.

◆ hashValue()

template<typename BaseVecT , typename BoxT >
size_t lvr2::HashGrid< BaseVecT, BoxT >::hashValue ( int  i,
int  j,
int  k 
) const
inline

Calculates the hash value for the given index triple.

Definition at line 252 of file HashGrid.hpp.

◆ lastCell()

template<typename BaseVecT , typename BoxT >
box_map_it lvr2::HashGrid< BaseVecT, BoxT >::lastCell ( )
inline
Returns
Returns an iterator to the last box in the cell map.

Definition at line 210 of file HashGrid.hpp.

◆ lastQueryPoint()

template<typename BaseVecT , typename BoxT >
query_point_it lvr2::HashGrid< BaseVecT, BoxT >::lastQueryPoint ( )
inline

Definition at line 220 of file HashGrid.hpp.

◆ saveCells()

template<typename BaseVecT , typename BoxT >
void lvr2::HashGrid< BaseVecT, BoxT >::saveCells ( string  file)

Saves a representation of the cells to the given file.

Parameters
fileOutput file name.

◆ saveGrid()

template<typename BaseVecT , typename BoxT >
virtual void lvr2::HashGrid< BaseVecT, BoxT >::saveGrid ( string  file)
virtual

Saves a representation of the grid to the given file.

Parameters
fileOutput file name.

Implements lvr2::GridBase.

◆ serialize()

template<typename BaseVecT , typename BoxT >
virtual void lvr2::HashGrid< BaseVecT, BoxT >::serialize ( string  file)
virtual

◆ setBB()

template<typename BaseVecT , typename BoxT >
void lvr2::HashGrid< BaseVecT, BoxT >::setBB ( BoundingBox< BaseVecT > &  bb)

◆ setCoordinateScaling()

template<typename BaseVecT , typename BoxT >
void lvr2::HashGrid< BaseVecT, BoxT >::setCoordinateScaling ( float  x,
float  y,
float  z 
)

Set x, y, z values to scale the scene or use combinations of +/-1 to mapp different coordinate systems.

Member Data Documentation

◆ m_boundingBox

template<typename BaseVecT , typename BoxT >
BoundingBox<BaseVecT> lvr2::HashGrid< BaseVecT, BoxT >::m_boundingBox
protected

Bounding box of the covered volume.

Definition at line 316 of file HashGrid.hpp.

◆ m_boxType

template<typename BaseVecT , typename BoxT >
string lvr2::HashGrid< BaseVecT, BoxT >::m_boxType
protected

True if a local tetraeder decomposition is used for reconstruction.

Definition at line 313 of file HashGrid.hpp.

◆ m_cells

template<typename BaseVecT , typename BoxT >
box_map lvr2::HashGrid< BaseVecT, BoxT >::m_cells
protected

Map to handle the boxes in the grid.

Definition at line 287 of file HashGrid.hpp.

◆ m_coordinateScales

template<typename BaseVecT , typename BoxT >
BaseVecT lvr2::HashGrid< BaseVecT, BoxT >::m_coordinateScales
protected

Save scaling factors (i.e., -1 or +1) to mapp different coordinate systems.

Definition at line 322 of file HashGrid.hpp.

◆ m_globalIndex

template<typename BaseVecT , typename BoxT >
unsigned int lvr2::HashGrid< BaseVecT, BoxT >::m_globalIndex
protected

The maximum used cell index within the grid.

Definition at line 319 of file HashGrid.hpp.

◆ m_maxIndex

template<typename BaseVecT , typename BoxT >
size_t lvr2::HashGrid< BaseVecT, BoxT >::m_maxIndex
protected

The absolute maximal index of the reconstruction grid.

Definition at line 295 of file HashGrid.hpp.

◆ m_maxIndexSquare

template<typename BaseVecT , typename BoxT >
size_t lvr2::HashGrid< BaseVecT, BoxT >::m_maxIndexSquare
protected

The squared maximal index of the reconstruction grid.

Definition at line 298 of file HashGrid.hpp.

◆ m_maxIndexX

template<typename BaseVecT , typename BoxT >
size_t lvr2::HashGrid< BaseVecT, BoxT >::m_maxIndexX
protected

The maximal index in x direction.

Definition at line 301 of file HashGrid.hpp.

◆ m_maxIndexY

template<typename BaseVecT , typename BoxT >
size_t lvr2::HashGrid< BaseVecT, BoxT >::m_maxIndexY
protected

The maximal index in y direction.

Definition at line 304 of file HashGrid.hpp.

◆ m_maxIndexZ

template<typename BaseVecT , typename BoxT >
size_t lvr2::HashGrid< BaseVecT, BoxT >::m_maxIndexZ
protected

The maximal index in z direction.

Definition at line 307 of file HashGrid.hpp.

◆ m_qpIndices

template<typename BaseVecT , typename BoxT >
qp_map lvr2::HashGrid< BaseVecT, BoxT >::m_qpIndices
protected

Definition at line 289 of file HashGrid.hpp.

◆ m_queryPoints

template<typename BaseVecT , typename BoxT >
vector<QueryPoint<BaseVecT> > lvr2::HashGrid< BaseVecT, BoxT >::m_queryPoints
protected

A vector containing the query points for the reconstruction.

Definition at line 310 of file HashGrid.hpp.

◆ m_voxelsize

template<typename BaseVecT , typename BoxT >
float lvr2::HashGrid< BaseVecT, BoxT >::m_voxelsize
protected

The voxelsize used for reconstruction.

Definition at line 292 of file HashGrid.hpp.

◆ qp_bb

template<typename BaseVecT , typename BoxT >
BoundingBox<BaseVecT> lvr2::HashGrid< BaseVecT, BoxT >::qp_bb

Definition at line 98 of file HashGrid.hpp.


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


lvr2
Author(s): Thomas Wiemann , Sebastian Pütz , Alexander Mock , Lars Kiesow , Lukas Kalbertodt , Tristan Igelbrink , Johan M. von Behren , Dominik Feldschnieders , Alexander Löhr
autogenerated on Wed Mar 2 2022 00:37:27