Public Types | Public Member Functions | Private Member Functions | List of all members
lvr2::ChunkManager Class Reference

#include <ChunkManager.hpp>

Inheritance diagram for lvr2::ChunkManager:
Inheritance graph
[legend]

Public Types

using FilterFunction = std::function< bool(MultiChannelMap::val_type, size_t)>
 
- Public Types inherited from lvr2::ChunkHashGrid
using io = Hdf5Build< hdf5features::ChunkIO >
 
using val_type = boost::variant< MeshBufferPtr, PointBufferPtr >
 

Public Member Functions

void buildChunks (MeshBufferPtr mesh, float maxChunkOverlap, std::string savePath, std::string layer=std::string("mesh"))
 buildChunks builds chunks from an original mesh More...
 
 ChunkManager (MeshBufferPtr meshes, float chunksize, float maxChunkOverlap, std::string savePath, std::string layer=std::string("mesh"), size_t cacheSize=200)
 ChunkManager creates chunks from an original mesh. More...
 
 ChunkManager (std::string hdf5Path, size_t cacheSize=200, float chunkSize=10.0f)
 ChunkManager loads a ChunkManager from a given HDF5-file. More...
 
 ChunkManager (std::vector< MeshBufferPtr > meshes, float chunksize, float maxChunkOverlap, std::string savePath, std::vector< std::string > layers, size_t cacheSize=200)
 
void extractArea (const BoundingBox< BaseVector< float > > &area, std::unordered_map< std::size_t, MeshBufferPtr > &chunks, std::string layer=std::string("mesh"))
 
MeshBufferPtr extractArea (const BoundingBox< BaseVector< float >> &area, const std::map< std::string, FilterFunction > filter, std::string layer=std::string("mesh"))
 extractArea creates and returns MeshBufferPtr of merged chunks for given area after filtering the resulting mesh. More...
 
MeshBufferPtr extractArea (const BoundingBox< BaseVector< float >> &area, std::string layer=std::string("mesh"))
 extractArea creates and returns MeshBufferPtr of merged chunks for given area. More...
 
std::vector< std::string > getChannelsFromMesh (std::string layer=std::string("mesh"))
 Get all existing channels from mesh. More...
 
BoundingBox< BaseVector< float > > getGlobalBoundingBox ()
 getGlobalBoundingBox is a getter for the bounding box of the entire chunked model More...
 
void loadAllChunks (std::string layer=std::string("mesh"))
 Loads all chunks into the ChunkHashGrid. DEBUG – Only used for testing, but might be useful for smaller meshes. More...
 
- Public Member Functions inherited from lvr2::ChunkHashGrid
 ChunkHashGrid (std::string hdf5Path, size_t cacheSize, BoundingBox< BaseVector< float >> boundingBox, float chunkSize)
 class to load chunks from an HDF5 file More...
 
 ChunkHashGrid (std::string hdf5Path, size_t cacheSize, float chunkSize=10.0f)
 class to load chunks from an HDF5 file More...
 
const BoundingBox< BaseVector< float > > & getBoundingBox () const
 
template<typename T >
boost::optional< T > getChunk (std::string layer, int x, int y, int z)
 delivers the content of a chunk More...
 
const BaseVector< std::size_t > & getChunkAmount () const
 
BaseVector< int > getChunkMaxChunkIndex () const
 returns the maximum chunk ids More...
 
BaseVector< int > getChunkMinChunkIndex () const
 returns the minimum chunk ids More...
 
float getChunkSize () const
 
std::size_t hashValue (int i, int j, int k) const
 Calculates the hash value for the given index triple. More...
 
bool isChunkLoaded (std::string layer, int x, int y, int z)
 indicates if wether or not a chunk is currently loaded in the local cache More...
 
bool isChunkLoaded (std::string layer, size_t hashValue)
 indicates if wether or not a chunk is currently loaded in the local cache More...
 
void setBoundingBox (const BoundingBox< BaseVector< float >> boundingBox)
 sets the bounding box in this container and in persistend storage More...
 
template<typename T >
void setChunk (std::string layer, int x, int y, int z, T data)
 sets a chunk of a given layer in hashgrid More...
 
template<typename T >
void setGeometryChunk (std::string layer, int x, int y, int z, T data)
 sets a chunk of a given layer in hashgrid More...
 

Private Member Functions

template<typename T >
MultiChannelMap::val_type applyChannelFilter (const std::vector< bool > &vertexFilter, const std::vector< bool > &faceFilter, const size_t numVertices, const size_t numFaces, const MeshBufferPtr meshBuffer, const MultiChannelMap::val_type &originalChannel) const
 applies given filter arrays to one channel More...
 
void cutLargeFaces (std::shared_ptr< HalfEdgeMesh< BaseVector< float >>> halfEdgeMesh, float overlapRatio, std::shared_ptr< std::unordered_map< unsigned int, unsigned int >> splitVertices, std::shared_ptr< std::unordered_map< unsigned int, unsigned int >> splitFaces)
 cutLargeFaces cuts a face if it is too large More...
 
template<typename T >
ChannelPtr< T > extractChannelOfArea (std::unordered_map< std::size_t, MeshBufferPtr > &chunks, std::string channelName, std::size_t staticVertexIndexOffset, std::size_t numVertices, std::size_t numFaces, std::vector< std::unordered_map< std::size_t, std::size_t >> &areaVertexIndices)
 reads and combines a channel of multiple chunks More...
 
BaseVector< int > getCellCoordinates (const BaseVector< float > &vec) const
 returns the grid coordinates of a given point More...
 
BaseVector< float > getFaceCenter (std::shared_ptr< HalfEdgeMesh< BaseVector< float >>> mesh, const FaceHandle &handle) const
 getFaceCenter gets the center point for a given face More...
 
void initBoundingBox (MeshBufferPtr mesh)
 initBoundingBox calculates a bounding box of the original mesh More...
 

Additional Inherited Members

- Protected Member Functions inherited from lvr2::ChunkHashGrid
void expandBoundingBox (const val_type &data)
 
template<typename T >
bool loadChunk (std::string layer, int x, int y, int z)
 loads a chunk from persistent storage into cache More...
 
void loadChunk (std::string layer, int x, int y, int z, const val_type &data)
 loads given chunk data into cache More...
 
void rehashCache (const BaseVector< std::size_t > &oldChunkAmount, const BaseVector< std::size_t > &oldChunkIndexOffset)
 regenerates cache hash grid More...
 
void setChunkSize (float chunkSize)
 sets chunk size in this container and in persistent storage More...
 
- Protected Attributes inherited from lvr2::ChunkHashGrid
BoundingBox< BaseVector< float > > m_boundingBox
 

Detailed Description

Definition at line 50 of file ChunkManager.hpp.

Member Typedef Documentation

◆ FilterFunction

using lvr2::ChunkManager::FilterFunction = std::function<bool(MultiChannelMap::val_type, size_t)>

Definition at line 53 of file ChunkManager.hpp.

Constructor & Destructor Documentation

◆ ChunkManager() [1/3]

lvr2::ChunkManager::ChunkManager ( MeshBufferPtr  meshes,
float  chunksize,
float  maxChunkOverlap,
std::string  savePath,
std::string  layer = std::string("mesh"),
size_t  cacheSize = 200 
)

ChunkManager creates chunks from an original mesh.

Chunks the original model into chunks of given size. Every created chunk has the same length in height, width and depth.

Parameters
meshmesh to be chunked
chunksizesize of a chunk - unit depends on the given mesh
maxChunkOverlapmaximum allowed overlap between chunks relative to the chunk size. Larger triangles will be cut
savePathJUST FOR TESTING - REMOVE LATER ON
cacheSizemaximum number of chunks loaded in the ChunkHashGrid

Definition at line 66 of file ChunkManager.cpp.

◆ ChunkManager() [2/3]

lvr2::ChunkManager::ChunkManager ( std::vector< MeshBufferPtr meshes,
float  chunksize,
float  maxChunkOverlap,
std::string  savePath,
std::vector< std::string >  layers,
size_t  cacheSize = 200 
)

Definition at line 80 of file ChunkManager.cpp.

◆ ChunkManager() [3/3]

lvr2::ChunkManager::ChunkManager ( std::string  hdf5Path,
size_t  cacheSize = 200,
float  chunkSize = 10.0f 
)

ChunkManager loads a ChunkManager from a given HDF5-file.

Creates a ChunkManager from an already chunked HDF5 file and allows loading individual chunks and combining them to partial meshes. Every loaded chunk has the same length in height, width and depth.

Parameters
hdf5Pathpath to the HDF5 file, where chunks and additional information are stored
cacheSizemaximum number of chunks loaded in the ChunkHashGrid

Definition at line 110 of file ChunkManager.cpp.

Member Function Documentation

◆ applyChannelFilter()

template<typename T >
MultiChannelMap::val_type lvr2::ChunkManager::applyChannelFilter ( const std::vector< bool > &  vertexFilter,
const std::vector< bool > &  faceFilter,
const size_t  numVertices,
const size_t  numFaces,
const MeshBufferPtr  meshBuffer,
const MultiChannelMap::val_type originalChannel 
) const
private

applies given filter arrays to one channel

Template Parameters
TType of channels contents
Parameters
vertexFilterfilter array for vertices
faceFilterfilter array for faces
numVerticesamount of vertices after filtering
numFacesamount of faces after filtering
meshBufferoriginal mesh
originalChannelchannel to filter
Returns
a new filtered channel

◆ buildChunks()

void lvr2::ChunkManager::buildChunks ( MeshBufferPtr  mesh,
float  maxChunkOverlap,
std::string  savePath,
std::string  layer = std::string("mesh") 
)

buildChunks builds chunks from an original mesh

Creates chunks from an original mesh and initializes the initial chunk structure

Parameters
meshmesh which is being chunked
maxChunkOverlapmaximum allowed overlap between chunks relative to the chunk size. Larger triangles will be cut
savePathUST FOR TESTING - REMOVE LATER ON

Definition at line 652 of file ChunkManager.cpp.

◆ cutLargeFaces()

void lvr2::ChunkManager::cutLargeFaces ( std::shared_ptr< HalfEdgeMesh< BaseVector< float >>>  halfEdgeMesh,
float  overlapRatio,
std::shared_ptr< std::unordered_map< unsigned int, unsigned int >>  splitVertices,
std::shared_ptr< std::unordered_map< unsigned int, unsigned int >>  splitFaces 
)
private

cutLargeFaces cuts a face if it is too large

Checks whether or not a triangle is overlapping the chunk borders too much and cuts those faces. The resulting smaller faces will be added as additional vertices and faces to the chunk hat holds their center point.

Parameters
halfEdgeMeshmesh that is being cut
overlapRatioration of maximum allowed overlap and the chunks side length
splitVerticesmap from new vertex indices to old vertex indices for all faces that will be cut
splitFacesmap from new face indices to old face indices for all faces that will be cut

Definition at line 536 of file ChunkManager.cpp.

◆ extractArea() [1/3]

void lvr2::ChunkManager::extractArea ( const BoundingBox< BaseVector< float > > &  area,
std::unordered_map< std::size_t, MeshBufferPtr > &  chunks,
std::string  layer = std::string("mesh") 
)

◆ extractArea() [2/3]

MeshBufferPtr lvr2::ChunkManager::extractArea ( const BoundingBox< BaseVector< float >> &  area,
const std::map< std::string, FilterFunction filter,
std::string  layer = std::string("mesh") 
)

extractArea creates and returns MeshBufferPtr of merged chunks for given area after filtering the resulting mesh.

Finds corresponding chunks for given area inside the grid and merges those chunks to a new mesh without duplicated vertices. The new mesh is returned as MeshBufferPtr. After extracting the area, given filters are being applied to allow more precise quaries for use cases like robot navigation while minimizing network traffic.

example for a filter: std::map<std::string, lvr2::ChunkManager::FilterFunction> filter = {{"roughness", [](lvr2::MultiChannelMap::val_type channel, size_t index) { return channel.dataPtr<float>()[index] < 0.1; }}}; This filter will only use vertices that have a maximum roughness of 0,1. All Faces referencing the filtered vertices will be filtered too.

Parameters
areabounding box of the area to request
filtermap of filters with channel names as keys and functions as values
Returns
mesh of the given area

Definition at line 409 of file ChunkManager.cpp.

◆ extractArea() [3/3]

MeshBufferPtr lvr2::ChunkManager::extractArea ( const BoundingBox< BaseVector< float >> &  area,
std::string  layer = std::string("mesh") 
)

extractArea creates and returns MeshBufferPtr of merged chunks for given area.

Finds corresponding chunks for given area inside the grid and merges those chunks to a new mesh without duplicated vertices. The new mesh is returned as MeshBufferPtr.

Parameters
area
Returns
mesh of the given area

Definition at line 201 of file ChunkManager.cpp.

◆ extractChannelOfArea()

template<typename T >
ChannelPtr<T> lvr2::ChunkManager::extractChannelOfArea ( std::unordered_map< std::size_t, MeshBufferPtr > &  chunks,
std::string  channelName,
std::size_t  staticVertexIndexOffset,
std::size_t  numVertices,
std::size_t  numFaces,
std::vector< std::unordered_map< std::size_t, std::size_t >> &  areaVertexIndices 
)
private

reads and combines a channel of multiple chunks

Parameters
chunkslist of chunks to combine
channelNamename of channel to extract
staticVertexIndexOffsetamount of duplicate vertices in the combined mesh
numVerticesamount of vertices in the combined mesh
numFacesamount of faces in the combined mesh
areaVertexIndicesmapping from old vertex index to new vertex index per chunk

◆ getCellCoordinates()

BaseVector< int > lvr2::ChunkManager::getCellCoordinates ( const BaseVector< float > &  vec) const
private

returns the grid coordinates of a given point

Parameters
vecpoint of which we want the grid coordinates
Returns
the grid coordinates as a BaseVector

Definition at line 743 of file ChunkManager.cpp.

◆ getChannelsFromMesh()

std::vector< std::string > lvr2::ChunkManager::getChannelsFromMesh ( std::string  layer = std::string("mesh"))

Get all existing channels from mesh.

Returns
List of all channel names as vector

Definition at line 115 of file ChunkManager.cpp.

◆ getFaceCenter()

BaseVector< float > lvr2::ChunkManager::getFaceCenter ( std::shared_ptr< HalfEdgeMesh< BaseVector< float >>>  mesh,
const FaceHandle handle 
) const
private

getFaceCenter gets the center point for a given face

Parameters
verticesChannelchannel of mesh that holds the vertices
facesChannelchannel of mesh that holds the faces
faceIndexindex of the requested face
Returns
center point of the given face

Definition at line 735 of file ChunkManager.cpp.

◆ getGlobalBoundingBox()

BoundingBox<BaseVector<float> > lvr2::ChunkManager::getGlobalBoundingBox ( )
inline

getGlobalBoundingBox is a getter for the bounding box of the entire chunked model

Returns
global bounding box of chunked model

Definition at line 101 of file ChunkManager.hpp.

◆ initBoundingBox()

void lvr2::ChunkManager::initBoundingBox ( MeshBufferPtr  mesh)
private

initBoundingBox calculates a bounding box of the original mesh

This calculates the bounding box of the given model and saves it to m_boundingBox.

Parameters
meshmesh whose bounding box shall be calculated

Definition at line 525 of file ChunkManager.cpp.

◆ loadAllChunks()

void lvr2::ChunkManager::loadAllChunks ( std::string  layer = std::string("mesh"))

Loads all chunks into the ChunkHashGrid. DEBUG – Only used for testing, but might be useful for smaller meshes.

Definition at line 759 of file ChunkManager.cpp.


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


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