ChunkManager.cpp
Go to the documentation of this file.
1 
38 
39 #include "lvr2/io/ModelFactory.hpp"
40 
41 #include <algorithm>
42 #include <boost/filesystem.hpp>
43 #include <cmath>
44 
45 namespace
46 {
47 template <typename T>
48 struct VectorCapsule
49 {
50  private:
51  std::shared_ptr<std::vector<T>> arr_;
52 
53  public:
54  explicit VectorCapsule(std::vector<T>&& arr)
55  : arr_(std::make_shared<std::vector<T>>(std::move(arr)))
56  {
57  }
58  ~VectorCapsule() = default;
59  void operator()(void*) {}
60 };
61 } // namespace
62 
63 namespace lvr2
64 {
65 
67  float chunksize,
68  float maxChunkOverlap,
69  std::string savePath,
70  std::string layer,
71  size_t cacheSize)
72  : ChunkManager(std::vector<MeshBufferPtr>{mesh},
73  chunksize,
74  maxChunkOverlap,
75  savePath,
76  std::vector<std::string>{layer},
77  cacheSize)
78 {
79 }
80 ChunkManager::ChunkManager(std::vector<MeshBufferPtr> meshes,
81  float chunksize,
82  float maxChunkOverlap,
83  std::string savePath,
84  std::vector<std::string> layers,
85  size_t cacheSize)
86  : ChunkHashGrid(savePath + "/chunk_mesh.h5", cacheSize)
87 {
88  setChunkSize(chunksize);
89  if (meshes.size() != layers.size())
90  {
91  std::cerr << lvr2::timestamp << "Number of meshes and layers do not match: \n"
92  << "Num meshes: " << meshes.size() << "\n"
93  << "Num layers: " << layers.size() << std::endl;
94 
95  return;
96  }
97 
98  // TODO use biggest
99  for (size_t i = 0; i < meshes.size(); ++i)
100  {
101  initBoundingBox(meshes[i]);
102  }
103 
104  for (size_t i = 0; i < meshes.size(); ++i)
105  {
106  buildChunks(meshes[i], maxChunkOverlap, savePath, layers[i]);
107  }
108 }
109 
110 ChunkManager::ChunkManager(std::string hdf5Path, size_t cacheSize, float chunkSize)
111  : ChunkHashGrid(hdf5Path, cacheSize, chunkSize)
112 {
113 }
114 
115 std::vector<std::string> ChunkManager::getChannelsFromMesh(std::string layer)
116 {
117  std::vector<std::string> attributeList;
118 
119  MeshBufferPtr chunkPtr;
120  bool isChunkFound = false;
121  for (int x = getChunkMinChunkIndex().x; x < getChunkMaxChunkIndex().x && !isChunkFound; x++)
122  {
123  for (int y = getChunkMinChunkIndex().y; y < getChunkMaxChunkIndex().y && !isChunkFound; y++)
124  {
125  for (int z = getChunkMinChunkIndex().z; z < getChunkMaxChunkIndex().z && !isChunkFound;
126  z++)
127  {
128  boost::optional<MeshBufferPtr> requestedChunk
129  = getChunk<MeshBufferPtr>(layer, x, y, z);
130  if (requestedChunk)
131  {
132  chunkPtr = requestedChunk.get();
133  isChunkFound = true;
134  }
135  }
136  }
137  }
138 
139  if (isChunkFound)
140  {
141  for (auto channelIterator = chunkPtr->begin(); channelIterator != chunkPtr->end();
142  ++channelIterator)
143  {
144  attributeList.push_back(channelIterator->first);
145  }
146  }
147  return attributeList;
148 }
149 
151  std::unordered_map<std::size_t, MeshBufferPtr>& chunks,
152  std::string layer)
153 {
154  // adjust area to our maximum boundingBox
155  BaseVector<float> adjustedAreaMin, adjustedAreaMax;
156  adjustedAreaMax[0] = std::min(area.getMax()[0], getBoundingBox().getMax()[0]);
157  adjustedAreaMax[1] = std::min(area.getMax()[1], getBoundingBox().getMax()[1]);
158  adjustedAreaMax[2] = std::min(area.getMax()[2], getBoundingBox().getMax()[2]);
159  adjustedAreaMin[0] = std::max(area.getMin()[0], getBoundingBox().getMin()[0]);
160  adjustedAreaMin[1] = std::max(area.getMin()[1], getBoundingBox().getMin()[1]);
161  adjustedAreaMin[2] = std::max(area.getMin()[2], getBoundingBox().getMin()[2]);
162  BoundingBox<BaseVector<float>> adjustedArea
163  = BoundingBox<BaseVector<float>>(adjustedAreaMin, adjustedAreaMax);
164 
165  // find all required chunks
166  // TODO: check if we need + 1
167  const BaseVector<float> maxSteps
168  = (adjustedArea.getMax() - adjustedArea.getMin()) / getChunkSize();
169  for (std::size_t i = 0; i < maxSteps.x; ++i)
170  {
171  for (std::size_t j = 0; j < maxSteps.y; ++j)
172  {
173  for (std::size_t k = 0; k < maxSteps.z; ++k)
174  {
176  adjustedArea.getMin() + BaseVector<float>(i, j, k) * getChunkSize());
177  size_t cellIndex = hashValue(cellCoord.x, cellCoord.y, cellCoord.z);
178 
179  // if element is already loaded.
180  // if(chunks.find(cellIndex) != chunks.end())
181  //{
182  // continue;
183  //}
184 
185  boost::optional<MeshBufferPtr> loadedChunk
186  = getChunk<MeshBufferPtr>(layer, cellCoord.x, cellCoord.y, cellCoord.z);
187 
188  if (loadedChunk)
189  {
190  // TODO: remove saving tmp chunks later
191  // ModelFactory::saveModel(lvr2::ModelPtr(new lvr2::Model(loadedChunk)),
192  // "area/" + std::to_string(cellIndex) + ".ply");
193  chunks.insert({cellIndex, *loadedChunk});
194  }
195  }
196  }
197  }
198  // std::cout << "Num chunks " << chunks.size() << std::endl;
199 }
200 
202  std::string layer)
203 {
204  std::unordered_map<std::size_t, MeshBufferPtr> chunks;
205 
206  // adjust area to our maximum boundingBox
207  BaseVector<float> adjustedAreaMin, adjustedAreaMax;
208  adjustedAreaMax[0] = std::min(area.getMax()[0], getBoundingBox().getMax()[0]);
209  adjustedAreaMax[1] = std::min(area.getMax()[1], getBoundingBox().getMax()[1]);
210  adjustedAreaMax[2] = std::min(area.getMax()[2], getBoundingBox().getMax()[2]);
211  adjustedAreaMin[0] = std::max(area.getMin()[0], getBoundingBox().getMin()[0]);
212  adjustedAreaMin[1] = std::max(area.getMin()[1], getBoundingBox().getMin()[1]);
213  adjustedAreaMin[2] = std::max(area.getMin()[2], getBoundingBox().getMin()[2]);
214  BoundingBox<BaseVector<float>> adjustedArea
215  = BoundingBox<BaseVector<float>>(adjustedAreaMin, adjustedAreaMax);
216 
217  // find all required chunks
218  // TODO: check if we need + 1
219  const BaseVector<float> maxSteps
220  = (adjustedArea.getMax() - adjustedArea.getMin()) / getChunkSize();
221  for (std::size_t i = 0; i < maxSteps.x; ++i)
222  {
223  for (std::size_t j = 0; j < maxSteps.y; ++j)
224  {
225  for (std::size_t k = 0; k < maxSteps.z; ++k)
226  {
228  adjustedArea.getMin() + BaseVector<float>(i, j, k) * getChunkSize());
229  size_t cellIndex = hashValue(cellCoord.x, cellCoord.y, cellCoord.z);
230 
231  boost::optional<MeshBufferPtr> loadedChunk
232  = getChunk<MeshBufferPtr>(layer, cellCoord.x, cellCoord.y, cellCoord.z);
233  if (loadedChunk)
234  {
235  // TODO: remove saving tmp chunks later
237  "area/" + std::to_string(cellIndex) + ".ply");
238  chunks.insert({cellIndex, *loadedChunk});
239  }
240  }
241  }
242  }
243  std::cout << "Extracted " << chunks.size() << " Chunks" << std::endl;
244 
245  std::vector<float> areaDuplicateVertices;
246  std::vector<std::unordered_map<std::size_t, std::size_t>> areaVertexIndices;
247  std::vector<float> areaUniqueVertices;
248  for (auto chunkIt = chunks.begin(); chunkIt != chunks.end(); ++chunkIt)
249  {
250  MeshBufferPtr chunk = chunkIt->second;
251  FloatChannel chunkVertices = *(chunk->getChannel<float>("vertices"));
252  std::size_t numDuplicates = *chunk->getAtomic<unsigned int>("num_duplicates");
253  std::size_t numVertices = chunk->numVertices();
254  std::unordered_map<std::size_t, std::size_t> chunkVertexIndices;
255 
256  if (numVertices == 0)
257  {
258  continue;
259  }
260 
261  if ((chunkIt == chunks.begin() || areaDuplicateVertices.empty()) && numDuplicates > 0)
262  {
263  areaDuplicateVertices.insert(areaDuplicateVertices.end(),
264  chunkVertices.dataPtr().get(),
265  chunkVertices.dataPtr().get() + (numDuplicates * 3));
266  }
267 
268  for (std::size_t i = 0; i < numDuplicates; ++i)
269  {
270  const size_t areaDuplicateVerticesSize = areaDuplicateVertices.size();
271 
272  bool found = false;
273  for (std::size_t j = 0; j < areaDuplicateVerticesSize / 3; ++j)
274  {
275  if ((areaDuplicateVertices[j * 3] == chunkVertices[i][0])
276  && (areaDuplicateVertices[j * 3 + 1] == chunkVertices[i][1])
277  && (areaDuplicateVertices[j * 3 + 2] == chunkVertices[i][2]))
278  {
279  found = true;
280  chunkVertexIndices.insert({i, j});
281  break;
282  }
283  }
284 
285  if (!found)
286  {
287  areaDuplicateVertices.push_back(chunkVertices[i][0]);
288  areaDuplicateVertices.push_back(chunkVertices[i][1]);
289  areaDuplicateVertices.push_back(chunkVertices[i][2]);
290 
291  chunkVertexIndices.insert({i, areaDuplicateVertices.size() / 3 - 1});
292  }
293  }
294 
295  areaUniqueVertices.insert(areaUniqueVertices.end(),
296  chunkVertices.dataPtr().get() + (numDuplicates * 3),
297  (chunkVertices.dataPtr().get() + (numVertices * 3)));
298 
299  areaVertexIndices.push_back(chunkVertexIndices);
300  }
301 
302  std::vector<unsigned int> areaFaceIndices;
303  const std::size_t staticFaceIndexOffset = areaDuplicateVertices.size() / 3;
304  std::size_t dynFaceIndexOffset = 0;
305  auto areaVertexIndicesIt = areaVertexIndices.begin();
306  for (auto chunkIt = chunks.begin(); chunkIt != chunks.end(); ++chunkIt)
307  {
308  MeshBufferPtr chunk = chunkIt->second;
309  indexArray chunkFaceIndices = chunk->getFaceIndices();
310  std::size_t numDuplicates = *chunk->getAtomic<unsigned int>("num_duplicates");
311  std::size_t numVertices = chunk->numVertices();
312  std::size_t numFaces = chunk->numFaces();
313  std::size_t faceIndexOffset = staticFaceIndexOffset - numDuplicates + dynFaceIndexOffset;
314 
315  for (std::size_t i = 0; i < numFaces * 3; ++i)
316  {
317  std::size_t oldIndex = chunkFaceIndices[i];
318  auto it = (*areaVertexIndicesIt).find(oldIndex);
319  if (it != (*areaVertexIndicesIt).end())
320  {
321  areaFaceIndices.push_back(it->second);
322  }
323  else
324  {
325  areaFaceIndices.push_back(oldIndex + faceIndexOffset);
326  }
327  }
328  dynFaceIndexOffset += (numVertices - numDuplicates);
329  ++areaVertexIndicesIt;
330  }
331 
332  std::cout << "combine vertices" << std::endl;
333  std::cout << "Duplicates: " << areaDuplicateVertices.size() / 3 << std::endl;
334  std::cout << "Unique: " << areaUniqueVertices.size() / 3 << std::endl;
335  areaDuplicateVertices.insert(
336  areaDuplicateVertices.end(), areaUniqueVertices.begin(), areaUniqueVertices.end());
337 
338  std::size_t areaVertexNum = areaDuplicateVertices.size() / 3;
339  float* tmpVertices = areaDuplicateVertices.data();
340  floatArr vertexArr
341  = floatArr(tmpVertices, VectorCapsule<float>(std::move(areaDuplicateVertices)));
342 
343  std::size_t faceIndexNum = areaFaceIndices.size() / 3;
344  auto* tmpFaceIndices = areaFaceIndices.data();
345  indexArray faceIndexArr
346  = indexArray(tmpFaceIndices, VectorCapsule<unsigned int>(std::move(areaFaceIndices)));
347 
348  MeshBufferPtr areaMeshPtr(new MeshBuffer);
349  areaMeshPtr->setVertices(vertexArr, areaVertexNum);
350  areaMeshPtr->setFaceIndices(faceIndexArr, faceIndexNum);
351 
352  for (auto chunkIt = chunks.begin(); chunkIt != chunks.end(); ++chunkIt)
353  {
354  MeshBufferPtr chunk = chunkIt->second;
355  for (auto elem : *chunk)
356  {
357  if (elem.first != "vertices" && elem.first != "face_indices"
358  && elem.first != "num_duplicates")
359  {
360  if (areaMeshPtr->find(elem.first) == areaMeshPtr->end())
361  {
362 
363  if (elem.second.is_type<unsigned char>())
364  {
365  areaMeshPtr->template addChannel<unsigned char>(
366  extractChannelOfArea<unsigned char>(chunks,
367  elem.first,
368  staticFaceIndexOffset,
369  areaMeshPtr->numVertices(),
370  areaMeshPtr->numFaces(),
371  areaVertexIndices),
372  elem.first);
373  }
374  else if (elem.second.is_type<unsigned int>())
375  {
376  areaMeshPtr->template addChannel<unsigned int>(
377  extractChannelOfArea<unsigned int>(chunks,
378  elem.first,
379  staticFaceIndexOffset,
380  areaMeshPtr->numVertices(),
381  areaMeshPtr->numFaces(),
382  areaVertexIndices),
383  elem.first);
384  }
385  else if (elem.second.is_type<float>())
386  {
387  areaMeshPtr->template addChannel<float>(
388  extractChannelOfArea<float>(chunks,
389  elem.first,
390  staticFaceIndexOffset,
391  areaMeshPtr->numVertices(),
392  areaMeshPtr->numFaces(),
393  areaVertexIndices),
394  elem.first);
395  }
396  }
397  }
398  }
399  }
400 
401  std::cout << "Vertices: " << areaMeshPtr->numVertices()
402  << ", Faces: " << areaMeshPtr->numFaces() << std::endl;
403 
404  ModelFactory::saveModel(ModelPtr(new Model(areaMeshPtr)), "test1.ply");
405 
406  return areaMeshPtr;
407 }
408 
410  const std::map<std::string, FilterFunction> filter,
411  std::string layer)
412 {
413  MeshBufferPtr areaMesh = extractArea(area, layer);
414 
415  // filter elements
416  // filter lists: false is used to indicate that an element will not be used
417  std::vector<bool> vertexFilter(areaMesh->numVertices(), true);
418  std::vector<bool> faceFilter(areaMesh->numFaces(), true);
419  std::size_t numVertices = areaMesh->numVertices();
420  std::size_t numFaces = areaMesh->numFaces();
421 
422  for (auto channelFilter : filter)
423  {
424  if (areaMesh->find(channelFilter.first) != areaMesh->end())
425  {
426  MultiChannelMap::val_type channel = areaMesh->at(channelFilter.first);
427 #pragma omp parallel for
428  for (std::size_t i = 0; i < channel.numElements(); i++)
429  {
430  if (channel.numElements() == areaMesh->numVertices())
431  {
432  if (vertexFilter[i] == true)
433  {
434  vertexFilter[i] = channelFilter.second(channel, i);
435  if (vertexFilter[i] == false)
436  {
437  numVertices--;
438  }
439  }
440  }
441  else if (channel.numElements() == areaMesh->numFaces())
442  {
443  if (faceFilter[i] == true)
444  {
445  faceFilter[i] = channelFilter.second(channel, i);
446  if (faceFilter[i] == false)
447  {
448  numFaces--;
449  }
450  }
451  }
452  }
453  }
454  }
455 
456  // filter all faces that reference filtered vertices
457  IndexChannel facesChannel = *areaMesh->getIndexChannel("face_indices");
458  for (std::size_t i = 0; i < areaMesh->numFaces(); i++)
459  {
460  if (faceFilter[i] == true)
461  {
462  for (std::size_t j = 0; j < facesChannel.width(); j++)
463  {
464  if (vertexFilter[facesChannel[i][j]] == false)
465  {
466  faceFilter[i] = false;
467  numFaces--;
468  break;
469  }
470  }
471  }
472  }
473 
474  // create a mapping from old vertices to new vertices
475  std::vector<std::size_t> vertexIndexMapping(areaMesh->numVertices(), 0);
476  std::size_t tmpIndex = 0;
477  for (std::size_t i = 0; i < areaMesh->numVertices(); i++)
478  {
479  if (vertexFilter[i] == true)
480  {
481  vertexIndexMapping[i] = tmpIndex;
482  tmpIndex++;
483  }
484  }
485 
486  // remove filtered elements
487  // #pragma omp parallel
488  {
489  for (auto& channel : *areaMesh)
490  {
491  // #pragma omp single nowait
492  {
493  if (channel.second.is_type<unsigned char>())
494  {
495  channel.second = applyChannelFilter<unsigned char>(
496  vertexFilter, faceFilter, numVertices, numFaces, areaMesh, channel.second);
497  }
498  else if (channel.second.is_type<unsigned int>())
499  {
500  channel.second = applyChannelFilter<unsigned int>(
501  vertexFilter, faceFilter, numVertices, numFaces, areaMesh, channel.second);
502  }
503  else if (channel.second.is_type<float>())
504  {
505  channel.second = applyChannelFilter<float>(
506  vertexFilter, faceFilter, numVertices, numFaces, areaMesh, channel.second);
507  }
508  }
509  }
510  }
511 
512  // use mapping from old vertex indices to new vertex indices to update face indices
513  facesChannel = *areaMesh->getIndexChannel("face_indices");
514  for (std::size_t i = 0; i < areaMesh->numFaces(); i++)
515  {
516  for (std::size_t j = 0; j < facesChannel.width(); j++)
517  {
518  facesChannel[i][j] = vertexIndexMapping[facesChannel[i][j]];
519  }
520  }
521 
522  return areaMesh;
523 }
524 
526 {
527  BoundingBox<BaseVector<float>> boundingBox;
528  FloatChannel vertices = mesh->getFloatChannel("vertices").get();
529  for (unsigned int i = 0; i < vertices.numElements(); i++)
530  {
531  boundingBox.expand(static_cast<BaseVector<float>>(vertices[i]));
532  }
533  setBoundingBox(boundingBox);
534 }
535 
537  std::shared_ptr<HalfEdgeMesh<BaseVector<float>>> halfEdgeMesh,
538  float overlapRatio,
539  std::shared_ptr<std::unordered_map<unsigned int, unsigned int>> splitVertices,
540  std::shared_ptr<std::unordered_map<unsigned int, unsigned int>> splitFaces)
541 
542 {
543  // check all edges if they range too far into different chunks
544  MeshHandleIteratorPtr<EdgeHandle> iterator = halfEdgeMesh->edgesBegin();
545  while (iterator != halfEdgeMesh->edgesEnd())
546  {
547  // check both directions for each face
548  std::array<VertexHandle, 2> vertices = halfEdgeMesh->getVerticesOfEdge(*iterator);
549  for (unsigned int i = 0; i <= 1; i++)
550  {
551  VertexHandle referenceVertex = vertices[i];
552  VertexHandle comparedVertex = vertices[(i + 1) % 2];
553 
554  bool isLargeEdge = false;
555 
556  // check distance to nearest chunkBorder for all three directions
557  for (unsigned int axis = 0; axis < 3; axis++)
558  {
559  // key for size comparison depending on the current axis
560  float referenceVertexKey = halfEdgeMesh->getVertexPosition(referenceVertex)[axis];
561  float comparedVertexKey = halfEdgeMesh->getVertexPosition(comparedVertex)[axis];
562 
563  // if the edge goes over multiple chunks it is to large because of a chunk
564  // border located in the middle of the edge
565  if (fabs(referenceVertexKey - comparedVertexKey) > 2 * getChunkSize())
566  {
567  isLargeEdge = true;
568  break;
569  }
570 
571  // get coordinate for plane in direction of the current axis
572  float chunkBorder
573  = getChunkSize() * (static_cast<int>(referenceVertexKey / getChunkSize()))
574  + fmod(getBoundingBox().getMin()[axis], getChunkSize());
575 
576  // select plane of chunk depending on the relative position of the compared
577  // vertex
578  if (referenceVertexKey < comparedVertexKey)
579  {
580  chunkBorder += getChunkSize();
581  }
582 
583  // check whether or not to cut the face
584  if (referenceVertexKey - chunkBorder < 0 && comparedVertexKey - chunkBorder >= 0
585  && chunkBorder - referenceVertexKey > overlapRatio * getChunkSize()
586  && comparedVertexKey - chunkBorder > overlapRatio * getChunkSize())
587  {
588  isLargeEdge = true;
589  break;
590  }
591  else if (referenceVertexKey - chunkBorder >= 0
592  && comparedVertexKey - chunkBorder < 0
593  && referenceVertexKey - chunkBorder > overlapRatio * getChunkSize()
594  && chunkBorder - comparedVertexKey > overlapRatio * getChunkSize())
595  {
596  isLargeEdge = true;
597  break;
598  }
599  }
600 
601  if (isLargeEdge)
602  {
603  std::array<OptionalFaceHandle, 2> faces = halfEdgeMesh->getFacesOfEdge(*iterator);
604 
605  // build newIndex -> oldIndex map to use
606  unsigned int faceIndex = halfEdgeMesh->nextFaceIndex();
607  if (faces[0])
608  {
609  unsigned int face = faces[0].unwrap().idx();
610  while (splitFaces->find(face) != splitFaces->end())
611  {
612  face = splitFaces->at(face);
613  }
614  splitFaces->insert({faceIndex, face});
615  faceIndex++;
616  }
617  if (faces[1])
618  {
619  unsigned int face = faces[1].unwrap().idx();
620  while (splitFaces->find(face) != splitFaces->end())
621  {
622  face = splitFaces->at(face);
623  }
624  splitFaces->insert({faceIndex, face});
625  }
626 
627  unsigned int vertex = referenceVertex.idx();
628  while (splitVertices->find(vertex) != splitVertices->end())
629  {
630  vertex = splitVertices->at(vertex);
631  }
632  splitVertices->insert({halfEdgeMesh->nextVertexIndex(), vertex});
633 
634  // cut edge in half
635  float cutRatio = 0.5;
636  BaseVector<float> cutPoint
637  = halfEdgeMesh->getVertexPosition(referenceVertex) * cutRatio
638  + halfEdgeMesh->getVertexPosition(comparedVertex) * (1 - cutRatio);
639 
640  halfEdgeMesh->splitVertex(*iterator,
641  referenceVertex,
642  halfEdgeMesh->getVertexPosition(referenceVertex),
643  cutPoint);
644  break;
645  }
646  }
647 
648  ++iterator;
649  }
650 }
651 
653  float maxChunkOverlap,
654  std::string savePath,
655  std::string layer)
656 {
657  std::vector<ChunkBuilderPtr> chunkBuilders(getChunkAmount().x * getChunkAmount().y
658  * getChunkAmount().z);
659 
660  std::shared_ptr<HalfEdgeMesh<BaseVector<float>>> halfEdgeMesh
661  = std::shared_ptr<HalfEdgeMesh<BaseVector<float>>>(
663 
664  // map from new indices to old indices to allow attributes for cut faces
665  std::shared_ptr<std::unordered_map<unsigned int, unsigned int>> splitVertices(
666  new std::unordered_map<unsigned int, unsigned int>);
667  std::shared_ptr<std::unordered_map<unsigned int, unsigned int>> splitFaces(
668  new std::unordered_map<unsigned int, unsigned int>);
669 
670  // prepare mash to prevent faces from overlapping too much on chunk borders
671  cutLargeFaces(halfEdgeMesh, maxChunkOverlap, splitVertices, splitFaces);
672 
673  // one vector of variable size for each vertex - this is used for duplicate detection
674  std::shared_ptr<std::unordered_map<unsigned int, std::vector<std::weak_ptr<ChunkBuilder>>>>
675  vertexUse(new std::unordered_map<unsigned int, std::vector<std::weak_ptr<ChunkBuilder>>>());
676 
677  for (int i = getChunkMinChunkIndex().x; i < getChunkMaxChunkIndex().x; i++)
678  {
679  for (int j = getChunkMinChunkIndex().y; j < getChunkMaxChunkIndex().y; j++)
680  {
681  for (int k = getChunkMinChunkIndex().z; k < getChunkMaxChunkIndex().z; k++)
682  {
683  chunkBuilders[hashValue(i, j, k)]
684  = ChunkBuilderPtr(new ChunkBuilder(halfEdgeMesh, vertexUse));
685  }
686  }
687  }
688 
689  // assign the faces to the chunks
690  BaseVector<float> currentCenterPoint;
691  MeshHandleIteratorPtr<FaceHandle> iterator = halfEdgeMesh->facesBegin();
692  for (size_t i = 0; i < halfEdgeMesh->numFaces(); i++)
693  {
694  currentCenterPoint = getFaceCenter(halfEdgeMesh, *iterator);
695  BaseVector<int> cellCorrdinate = getCellCoordinates(currentCenterPoint);
696  size_t hash = hashValue(cellCorrdinate.x, cellCorrdinate.y, cellCorrdinate.z);
697 
698  chunkBuilders[hash]->addFace(*iterator);
699 
700  ++iterator;
701  }
702 
703  // save the chunks as .ply
704  for (int i = getChunkMinChunkIndex().x; i < getChunkMaxChunkIndex().x; i++)
705  {
706  for (int j = getChunkMinChunkIndex().y; j < getChunkMaxChunkIndex().y; j++)
707  {
708  for (int k = getChunkMinChunkIndex().z; k < getChunkMaxChunkIndex().z; k++)
709  {
710  std::size_t hash = hashValue(i, j, k);
711 
712  if (chunkBuilders[hash]->numFaces() > 0)
713  {
714  // std::cout << "writing " << i << " " << j << " " << k << std::endl;
715 
716  // get mesh of chunk from chunk builder
717  MeshBufferPtr chunkMeshPtr
718  = chunkBuilders[hash]->buildMesh(mesh, splitVertices, splitFaces);
719 
720  // export chunked meshes for debugging
721  // ModelFactory::saveModel(ModelPtr(new Model(chunkMeshPtr)),
722  // savePath + "/" + std::to_string(i) + "-"
723  // + std::to_string(j) + "-" + std::to_string(k)
724  // + ".ply");
725  // write chunk in hdf5
726  setChunk<MeshBufferPtr>(layer, i, j, k, chunkMeshPtr);
727 
728  chunkBuilders[hash] = nullptr; // deallocate
729  }
730  }
731  }
732  }
733 }
734 
736  const FaceHandle& handle) const
737 {
738  return (mesh->getVertexPositionsOfFace(handle)[0] + mesh->getVertexPositionsOfFace(handle)[1]
739  + mesh->getVertexPositionsOfFace(handle)[2])
740  / 3;
741 }
742 
744 {
745  BaseVector<float> tmpVec = vec / getChunkSize();
747  static_cast<int>(tmpVec.x), static_cast<int>(tmpVec.y), static_cast<int>(tmpVec.z));
748  return ret;
749 }
750 
751 // std::string ChunkManager::getCellName(const BaseVector<float>& vec) const
752 //{
753 // BaseVector<float> tmpVec = (vec - getBoundingBox().getMin()) / getChunkSize();
754 // return std::to_string(static_cast<size_t>(tmpVec.x)) + "_"+
755 // std::to_string(static_cast<size_t>(tmpVec.y)) + "_"
756 // + std::to_string(static_cast<size_t>(tmpVec.z));
757 //}
758 
759 void ChunkManager::loadAllChunks(std::string layer)
760 {
761  int numLoaded = 0;
762  for (int i = 0; i < getChunkAmount()[0]; i++)
763  {
764  for (int j = 0; j < getChunkAmount()[1]; j++)
765  {
766  for (int k = 0; k < getChunkAmount()[2]; k++)
767  {
768  if (loadChunk<MeshBufferPtr>(layer, i, j, k))
769  {
770  numLoaded++;
771  }
772  }
773  }
774  }
775 
776  std::cout << "loaded " << numLoaded << " chunks from hdf5-file." << std::endl;
777 }
778 
779 } /* namespace lvr2 */
lvr2::floatArr
boost::shared_array< float > floatArr
Definition: DataStruct.hpp:133
lvr2::ModelFactory::saveModel
static void saveModel(ModelPtr m, std::string file)
Definition: ModelFactory.cpp:225
lvr2::BaseVector< float >
lvr2::ChunkHashGrid::setBoundingBox
void setBoundingBox(const BoundingBox< BaseVector< float >> boundingBox)
sets the bounding box in this container and in persistend storage
Definition: ChunkHashGrid.cpp:172
lvr2::ChunkHashGrid::getBoundingBox
const BoundingBox< BaseVector< float > > & getBoundingBox() const
Definition: ChunkHashGrid.hpp:180
lvr2::indexArray
boost::shared_array< unsigned int > indexArray
Definition: DataStruct.hpp:128
lvr2::FaceHandle
Handle to access faces of the mesh.
Definition: Handles.hpp:140
lvr2::ChunkBuilderPtr
std::shared_ptr< ChunkBuilder > ChunkBuilderPtr
Definition: ChunkBuilder.hpp:48
lvr2::BoundingBox::getMax
BaseVecT getMax() const
Returns the upper right coordinates.
lvr2::ChunkBuilder
Definition: ChunkBuilder.hpp:50
lvr2::ChunkHashGrid
Definition: ChunkHashGrid.hpp:67
lvr2::BaseVector::x
CoordT x
Definition: BaseVector.hpp:65
lvr2::Model
Definition: Model.hpp:51
lvr2::ChunkHashGrid::hashValue
std::size_t hashValue(int i, int j, int k) const
Calculates the hash value for the given index triple.
Definition: ChunkHashGrid.hpp:174
lvr2::ChunkHashGrid::getChunkSize
float getChunkSize() const
Definition: ChunkHashGrid.hpp:185
lvr2::MeshBuffer
The MeshBuffer Mesh representation for I/O modules.
Definition: MeshBuffer.hpp:41
lvr2::ChunkManager::getChannelsFromMesh
std::vector< std::string > getChannelsFromMesh(std::string layer=std::string("mesh"))
Get all existing channels from mesh.
Definition: ChunkManager.cpp:115
lvr2::BaseVector::y
CoordT y
Definition: BaseVector.hpp:66
lvr2::VertexHandle
Handle to access vertices of the mesh.
Definition: Handles.hpp:146
lvr2::Channel::dataPtr
const DataPtr dataPtr() const
lvr2::ChunkHashGrid::getChunkAmount
const BaseVector< std::size_t > & getChunkAmount() const
Definition: ChunkHashGrid.hpp:190
lvr2::timestamp
static Timestamp timestamp
A global time stamp object for program runtime measurement.
Definition: Timestamp.hpp:116
lvr2::ChunkHashGrid::getChunkMinChunkIndex
BaseVector< int > getChunkMinChunkIndex() const
returns the minimum chunk ids
Definition: ChunkHashGrid.hpp:198
lvr2::ChunkManager::buildChunks
void buildChunks(MeshBufferPtr mesh, float maxChunkOverlap, std::string savePath, std::string layer=std::string("mesh"))
buildChunks builds chunks from an original mesh
Definition: ChunkManager.cpp:652
lvr2::ChunkManager::getFaceCenter
BaseVector< float > getFaceCenter(std::shared_ptr< HalfEdgeMesh< BaseVector< float >>> mesh, const FaceHandle &handle) const
getFaceCenter gets the center point for a given face
Definition: ChunkManager.cpp:735
lvr2::ChunkManager::initBoundingBox
void initBoundingBox(MeshBufferPtr mesh)
initBoundingBox calculates a bounding box of the original mesh
Definition: ChunkManager.cpp:525
lvr2::VariantChannel::numElements
size_t numElements() const
lvr2::ChunkManager::loadAllChunks
void loadAllChunks(std::string layer=std::string("mesh"))
Loads all chunks into the ChunkHashGrid. DEBUG – Only used for testing, but might be useful for small...
Definition: ChunkManager.cpp:759
filter
void filter(lvr2::PointBufferPtr &cloud, lvr2::indexArray &inlier, size_t j)
Definition: src/tools/lvr2_cl_sor/Main.cpp:40
lvr2::BoundingBox
A dynamic bounding box class.
Definition: BoundingBox.hpp:49
lvr2::Channel< float >
lvr2::ChunkManager::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.
Definition: ChunkManager.cpp:66
lvr2::BaseVector::z
CoordT z
Definition: BaseVector.hpp:67
lvr2::BoundingBox::expand
void expand(T v)
Expands the bounding box if the given Vector v} is outside the current volume.
std
Definition: HalfEdge.hpp:124
lvr2::ChunkManager::extractArea
MeshBufferPtr extractArea(const BoundingBox< BaseVector< float >> &area, std::string layer=std::string("mesh"))
extractArea creates and returns MeshBufferPtr of merged chunks for given area.
Definition: ChunkManager.cpp:201
lvr2
Definition: BaseBufferManipulators.hpp:39
lvr2::ModelPtr
std::shared_ptr< Model > ModelPtr
Definition: Model.hpp:80
lvr2::VariantChannel
Definition: VariantChannel.hpp:18
lvr2::ChunkManager::getCellCoordinates
BaseVector< int > getCellCoordinates(const BaseVector< float > &vec) const
returns the grid coordinates of a given point
Definition: ChunkManager.cpp:743
lvr2::MeshBufferPtr
std::shared_ptr< MeshBuffer > MeshBufferPtr
Definition: MeshBuffer.hpp:217
ModelFactory.hpp
lvr2::Channel::width
size_t width() const
lvr2::ChunkHashGrid::setChunkSize
void setChunkSize(float chunkSize)
sets chunk size in this container and in persistent storage
Definition: ChunkHashGrid.hpp:268
lvr2::ChunkHashGrid::getChunkMaxChunkIndex
BaseVector< int > getChunkMaxChunkIndex() const
returns the maximum chunk ids
Definition: ChunkHashGrid.hpp:207
lvr2::ChunkManager::cutLargeFaces
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
Definition: ChunkManager.cpp:536
ChunkManager.hpp
mesh
HalfEdgeMesh< Vec > mesh
Definition: src/tools/lvr2_gs_reconstruction/Main.cpp:26
lvr2::MeshHandleIteratorPtr
A wrapper for the MeshHandleIterator to save beloved future programmers from dereferencing too much <...
Definition: BaseMesh.hpp:81
lvr2::ChunkManager
Definition: ChunkManager.hpp:50
lvr2::BoundingBox::getMin
BaseVecT getMin() const
Returns the lower left coordinates.
lvr2::BaseHandle::idx
IdxT idx() const
lvr2::HalfEdgeMesh
Half-edge data structure implementing the BaseMesh interface.
Definition: HalfEdgeMesh.hpp:70
lvr2::Channel::numElements
size_t numElements() const


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:23