#include <HashGrid.hpp>

| 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 | 
Definition at line 94 of file HashGrid.hpp.
| 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.
| 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.
| typedef unordered_map<size_t, size_t> lvr2::HashGrid< BaseVecT, BoxT >::qp_map | 
Definition at line 103 of file HashGrid.hpp.
| 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.
| lvr2::HashGrid< BaseVecT, BoxT >::HashGrid | ( | float | cellSize, | 
| BoundingBox< BaseVecT > | boundingBox, | ||
| bool | isVoxelSize = true, | ||
| bool | extrude = true | ||
| ) | 
| lvr2::HashGrid< BaseVecT, BoxT >::HashGrid | ( | string | file | ) | 
| lvr2::HashGrid< BaseVecT, BoxT >::HashGrid | ( | std::vector< string > & | files, | 
| BoundingBox< BaseVecT > & | boundingBox, | ||
| float | voxelsize | ||
| ) | 
| lvr2::HashGrid< BaseVecT, BoxT >::HashGrid | ( | std::vector< string > & | files, | 
| std::vector< BoundingBox< BaseVecT >> | innerBoxes, | ||
| BoundingBox< BaseVecT > & | boundingBox, | ||
| float | voxelsize | ||
| ) | 
| lvr2::HashGrid< BaseVecT, BoxT >::HashGrid | ( | std::vector< PointBufferPtr > | chunks, | 
| std::vector< BoundingBox< BaseVecT >> | innerBoxes, | ||
| BoundingBox< BaseVecT > & | boundingBox, | ||
| float | voxelSize | ||
| ) | 
| 
 | virtual | 
| 
 | virtual | 
| i | Discrete x position within the grid. | 
| j | Discrete y position within the grid. | 
| k | Discrete z position within the grid. | 
| distance | Signed distance to the represented surface at the position within the grid. | 
Implements lvr2::GridBase.
| 
 | inlineprotected | 
Definition at line 281 of file HashGrid.hpp.
| void lvr2::HashGrid< BaseVecT, BoxT >::calcIndices | ( | ) | 
Calculates needed lattice parameters.
| 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.
| position | Number of a possible neighbor | 
| x | x index within the grid | 
| y | y index within the grid | 
| z | z index within the grid | 
| 
 | inline | 
Definition at line 205 of file HashGrid.hpp.
| 
 | inline | 
Definition at line 215 of file HashGrid.hpp.
| 
 | inline | 
Definition at line 247 of file HashGrid.hpp.
| 
 | inline | 
Definition at line 224 of file HashGrid.hpp.
| 
 | inline | 
Definition at line 237 of file HashGrid.hpp.
| 
 | inline | 
Definition at line 239 of file HashGrid.hpp.
| 
 | inline | 
Definition at line 241 of file HashGrid.hpp.
| 
 | inline | 
Definition at line 243 of file HashGrid.hpp.
| 
 | inline | 
Definition at line 200 of file HashGrid.hpp.
| 
 | inline | 
Definition at line 222 of file HashGrid.hpp.
| 
 | inline | 
Calculates the hash value for the given index triple.
Definition at line 252 of file HashGrid.hpp.
| 
 | inline | 
Definition at line 210 of file HashGrid.hpp.
| 
 | inline | 
Definition at line 220 of file HashGrid.hpp.
| void lvr2::HashGrid< BaseVecT, BoxT >::saveCells | ( | string | file | ) | 
Saves a representation of the cells to the given file.
| file | Output file name. | 
| 
 | virtual | 
Saves a representation of the grid to the given file.
| file | Output file name. | 
Implements lvr2::GridBase.
| 
 | virtual | 
| void lvr2::HashGrid< BaseVecT, BoxT >::setBB | ( | BoundingBox< BaseVecT > & | bb | ) | 
| 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.
| 
 | protected | 
Bounding box of the covered volume.
Definition at line 316 of file HashGrid.hpp.
| 
 | protected | 
True if a local tetraeder decomposition is used for reconstruction.
Definition at line 313 of file HashGrid.hpp.
| 
 | protected | 
Map to handle the boxes in the grid.
Definition at line 287 of file HashGrid.hpp.
| 
 | protected | 
Save scaling factors (i.e., -1 or +1) to mapp different coordinate systems.
Definition at line 322 of file HashGrid.hpp.
| 
 | protected | 
The maximum used cell index within the grid.
Definition at line 319 of file HashGrid.hpp.
| 
 | protected | 
The absolute maximal index of the reconstruction grid.
Definition at line 295 of file HashGrid.hpp.
| 
 | protected | 
The squared maximal index of the reconstruction grid.
Definition at line 298 of file HashGrid.hpp.
| 
 | protected | 
The maximal index in x direction.
Definition at line 301 of file HashGrid.hpp.
| 
 | protected | 
The maximal index in y direction.
Definition at line 304 of file HashGrid.hpp.
| 
 | protected | 
The maximal index in z direction.
Definition at line 307 of file HashGrid.hpp.
| 
 | protected | 
Definition at line 289 of file HashGrid.hpp.
| 
 | protected | 
A vector containing the query points for the reconstruction.
Definition at line 310 of file HashGrid.hpp.
| 
 | protected | 
The voxelsize used for reconstruction.
Definition at line 292 of file HashGrid.hpp.
| BoundingBox<BaseVecT> lvr2::HashGrid< BaseVecT, BoxT >::qp_bb | 
Definition at line 98 of file HashGrid.hpp.