HDF5IO.cpp
Go to the documentation of this file.
1 
28 #include "lvr2/io/HDF5IO.hpp"
29 
30 #include <boost/filesystem.hpp>
31 
32 #include <chrono>
33 #include <ctime>
34 #include <algorithm>
35 
36 namespace lvr2
37 {
38 
39 const std::string HDF5IO::vertices_name = "vertices";
40 const std::string HDF5IO::indices_name = "indices";
41 const std::string HDF5IO::meshes_group = "meshes";
42 
43 HDF5IO::HDF5IO(const std::string filename, const std::string part_name, int open_flag) :
44  m_hdf5_file(nullptr),
45  m_compress(true),
46  m_chunkSize(1e7),
47  m_usePreviews(true),
49  m_part_name(part_name),
50  m_mesh_path(meshes_group+"/"+part_name)
51 {
52  std::cout << timestamp << " Try to open file \"" << filename << "\"..." << std::endl;
53  if(!open(filename, open_flag))
54  {
55  std::cerr << timestamp << " Could not open file \"" << filename << "\"!" << std::endl;
56  }
57 }
58 
59 HDF5IO::HDF5IO(std::string filename, int open_flag) :
60  m_hdf5_file(nullptr),
61  m_compress(true),
62  m_chunkSize(1e7),
63  m_usePreviews(true),
65  m_part_name("")
66 {
67  open(filename, open_flag); // TODO Open should not be in the constructor
68 }
69 
71 {
72  if(m_hdf5_file)
73  {
74  delete m_hdf5_file;
75  }
76 }
77 
78 void HDF5IO::setCompress(bool compress)
79 {
81 }
82 
83 void HDF5IO::setChunkSize(const size_t& size)
84 {
85  m_chunkSize = size;
86 }
87 
88 void HDF5IO::setPreviewReductionFactor(const unsigned int factor)
89 {
90  if (factor >= 1)
91  {
92  m_previewReductionFactor = factor;
93  }
94  else
95  {
97  }
98 }
99 
101 {
102  m_usePreviews = use;
103 }
104 
106 {
107  return m_compress;
108 }
109 
110 bool HDF5IO::deleteDataset(const char* name)
111 {
112  // delete returning non-negative means success
113  return H5Ldelete(m_hdf5_file->getId(), name, H5P_DEFAULT) >= 0; // laplid = H5P_DEFAULT
114 }
115 
117 {
118  return m_chunkSize;
119 }
120 
122 {
124  ModelPtr model_ptr(new Model);
125 
126  std::cout << timestamp << "HDF5IO: loading..." << std::endl;
127  // read mesh information
128  if(readMesh(model_ptr))
129  {
130  std::cout << timestamp << " Mesh successfully loaded." << std::endl;
131  } else {
132  std::cout << timestamp << " Mesh could not be loaded." << std::endl;
133  }
134 
135  // read pointcloud information out of scans
136  if(readPointCloud(model_ptr))
137  {
138  std::cout << timestamp << " PointCloud successfully loaded." << std::endl;
139  } else {
140  std::cout << timestamp << " PointCloud could not be loaded." << std::endl;
141  }
142 
143  return model_ptr;
144 }
145 
147 {
148  std::vector<ScanPtr> scans = getRawScans(true);
149  if(scans.size() == 0)
150  {
151  return false;
152  }
153 
154  size_t n_points_total = 0;
155  for(const ScanPtr& scan : scans)
156  {
157  n_points_total += scan->points->numPoints();
158  }
159 
160  floatArr points(new float[n_points_total * 3]);
161  BaseVector<float>* points_raw_it = reinterpret_cast<BaseVector<float>* >(
162  points.get()
163  );
164 
165  for(int i=0; i<scans.size(); i++)
166  {
167  size_t num_points = scans[i]->points->numPoints();
168  floatArr pts = scans[i]->points->getPointArray();
169 
170  Transformd T = scans[i]->poseEstimation;
171  T.transpose();
172 
173  BaseVector<float>* begin = reinterpret_cast<BaseVector<float>* >(pts.get());
174  BaseVector<float>* end = begin + num_points;
175 
176  while(begin != end)
177  {
178  const BaseVector<float>& cp = *begin;
179  *points_raw_it = T * cp;
180 
181  begin++;
182  points_raw_it++;
183  }
184  }
185 
186  model_ptr->m_pointCloud.reset(new PointBuffer(points, n_points_total));
187 
188  return true;
189 }
190 
191 bool HDF5IO::readMesh(ModelPtr model_ptr)
192 {
193  const std::string mesh_resource_path = "meshes/" + m_part_name;
194  const std::string vertices("vertices");
195  const std::string indices("indices");
196 
197  if(!exist(mesh_resource_path)){
198  return false;
199  } else {
200  auto mesh = getGroup(mesh_resource_path);
201 
202  if(!mesh.exist(vertices) || !mesh.exist(indices)){
203  std::cout << timestamp << " The mesh has to contain \"" << vertices
204  << "\" and \"" << indices << "\"" << std::endl;
205  std::cout << timestamp << " Return empty model pointer!" << std::endl;
206  return false;
207  }
208 
209  std::vector<size_t> vertexDims;
210  std::vector<size_t> faceDims;
211 
212  // read mesh buffer
213  floatArr vbuffer = getArray<float>(mesh_resource_path, vertices, vertexDims);
214  indexArray ibuffer = getArray<unsigned int>(mesh_resource_path, indices, faceDims);
215 
216  if(vertexDims[0] == 0)
217  {
218  return false;
219  }
220  if(!model_ptr->m_mesh)
221  {
222  model_ptr->m_mesh.reset(new MeshBuffer());
223  }
224 
225  model_ptr->m_mesh->setVertices(vbuffer, vertexDims[0]);
226 
227  model_ptr->m_mesh->setFaceIndices(ibuffer, faceDims[0]);
228  }
229  return true;
230 }
231 
232 bool HDF5IO::open(std::string filename, int open_flag)
233 {
234  // If file alredy exists, don't rewrite base structurec++11 init vector
235  bool have_to_init = false;
236 
237  boost::filesystem::path path(filename);
238  if( (!boost::filesystem::exists(path)) || (open_flag == HighFive::File::Truncate))
239  {
240  have_to_init = true;
241  }
242  // Try to open the given HDF5 file
243  m_hdf5_file = new HighFive::File(filename, open_flag);
244 
245  if (!m_hdf5_file->isValid())
246  {
247  return false;
248  }
249 
250 
251  if(have_to_init)
252  {
253  // Write default groupts to new HDF5 file
255  }
256 
257  return true;
258 }
259 
261 {
262  int version = 1;
263  m_hdf5_file->createDataSet<int>("version", HighFive::DataSpace::From(version)).write(version);
264  HighFive::Group raw_data_group = m_hdf5_file->createGroup("raw");
265 
266  // Create string with current time
267  std::chrono::system_clock::time_point now = std::chrono::system_clock::now();
268  std::time_t t_now= std::chrono::system_clock::to_time_t(now);
269  std::string time(ctime(&t_now));
270 
271  // Add current time to raw data group
272  raw_data_group.createDataSet<std::string>("created", HighFive::DataSpace::From(time)).write(time);
273  raw_data_group.createDataSet<std::string>("changed", HighFive::DataSpace::From(time)).write(time);
274 
275  // Create empty reference frame
276  //vector<float> frame = Matrix4<BaseVector<float>>().getVector();
277  //std::cout << frame.size() << std::endl;
278  //raw_data_group.createDataSet<float>("position", HighFive::DataSpace::From(frame)).write(frame);
279 
280 }
281 
282 void HDF5IO::save(std::string filename)
283 {
284 
285 }
286 
287 void HDF5IO::save(ModelPtr model, std::string filename)
288 {
290 
291  if(saveMesh(model))
292  {
293  std::cout << timestamp << " Mesh succesfully saved to " << filename << std::endl;
294  } else {
295  std::cout << timestamp << " Mesh could not saved to " << filename << std::endl;
296  }
297 }
298 
299 bool HDF5IO::saveMesh(ModelPtr model_ptr)
300 {
301  if(!model_ptr->m_mesh)
302  {
303  std::cout << timestamp << " Model does not contain a mesh" << std::endl;
304  return false;
305  }
306 
307  const std::string mesh_resource_path = "meshes/" + m_part_name;
308  const std::string vertices("vertices");
309  const std::string indices("indices");
310 
311 
312  if(exist(mesh_resource_path)){
313  std::cout << timestamp << " Mesh already exists in file!" << std::endl;
314  return false;
315  } else {
316 
317  auto mesh = getGroup(mesh_resource_path);
318 
319  if(mesh.exist(vertices) || mesh.exist(indices)){
320  std::cout << timestamp << " The mesh has to contain \"" << vertices
321  << "\" and \"" << indices << "\"" << std::endl;
322  std::cout << timestamp << " Return empty model pointer!" << std::endl;
323  return false;
324  }
325 
326  std::vector<size_t> vertexDims = {model_ptr->m_mesh->numVertices(), 3};
327  std::vector<size_t> faceDims = {model_ptr->m_mesh->numFaces(), 3};
328 
329  if(vertexDims[0] == 0)
330  {
331  std::cout << timestamp << " The mesh has 0 vertices" << std::endl;
332  return false;
333  }
334  if(faceDims[0] == 0)
335  {
336  std::cout << timestamp << " The mesh has 0 faces" << std::endl;
337  return false;
338  }
339 
340  addArray<float>(
341  mesh_resource_path,
342  vertices,
343  vertexDims,
344  model_ptr->m_mesh->getVertices()
345  );
346 
347  addArray<unsigned int>(
348  mesh_resource_path,
349  indices,
350  faceDims,
351  model_ptr->m_mesh->getFaceIndices()
352  );
353 
354  }
355 
356  return true;
357 
358 }
359 
360 Texture HDF5IO::getImage(std::string groupName, std::string datasetName)
361 {
362 
363  Texture ret;
364 
365  if (m_hdf5_file)
366  {
367  if (exist(groupName))
368  {
369  HighFive::Group g = getGroup(groupName, false);
370  ret = getImage(g, datasetName);
371  }
372  }
373 
374  return ret;
375 }
376 
377 Texture HDF5IO::getImage(HighFive::Group& g, std::string datasetName)
378 {
379  Texture ret;
380 
381  if (m_hdf5_file)
382  {
383  if (g.exist(datasetName))
384  {
385  long long unsigned int width, height, planes;
386  long long int npals;
387  char interlace[256];
388 
389  if (!H5IMis_image(g.getId(), datasetName.c_str()))
390  {
391  return ret;
392  }
393 
394  if (H5IMget_image_info(
395  g.getId(), datasetName.c_str(), &width, &height,
396  &planes, interlace, &npals) >= 0)
397  {
398  if (width && height && planes && npals == 0)
399  {
400  ret = Texture(0, width, height, planes, 1, 1.0);
401 
402  if (H5IMread_image(g.getId(), datasetName.c_str(), ret.m_data) < 0)
403  {
404  ret = Texture();
405  }
406  }
407  }
408  }
409  }
410 
411  return ret;
412 }
413 
414 std::vector<ScanPtr> HDF5IO::getRawScans(bool load_points)
415 {
416  std::string groupName = "/raw/scans/";
417  std::vector<ScanPtr> ret;
418 
419  if (!exist(groupName))
420  {
421  return ret;
422  }
423 
424  HighFive::Group root_group = getGroup(groupName);
425  size_t num_objects = root_group.getNumberObjects();
426 
427  for (size_t i = 0; i < num_objects; i++)
428  {
429  int pos_num;
430  std::string cur_scan_pos = root_group.getObjectName(i);
431 
432  if (std::sscanf(cur_scan_pos.c_str(), "position_%5d", &pos_num))
433  {
434  ScanPtr cur_pos = getSingleRawScan(pos_num, load_points);
435  ret.push_back(cur_pos);
436  }
437  }
438 
439  return ret;
440 
441 }
442 
443 
444 
445 // template<template<typename Base> typename ...ComponentTs>
446 // class Hdf5IO;
447 
448 
449 // template<template<typename Base> typename ComponentT>
450 // class Hdf5IO<ComponentT<Hdf5IO<ComponentT> > > : public ComponentT<Hdf5IO<ComponentT> >, public BaseHdf5IO
451 // {
452 // public:
453 // using ComponentT<Hdf5IO<ComponentT> >::save;
454 // };
455 
456 // // template<template<typename Base> typename ...ComponentT >
457 // template<template<typename Base1> typename ComponentT, template<typename Base2> typename ...ComponentTs >
458 // class Hdf5IO<ComponentT<Hdf5IO<ComponentT> >, ComponentTs<Hdf5IO<ComponentTs...> >...>
459 // : public ComponentT<Hdf5IO<ComponentT> >, public Hdf5IO<ComponentTs<Hdf5IO<ComponentTs...> >...>
460 // {
461 // public:
462 // using ComponentT<Hdf5IO<ComponentT> >::save;
463 // using Hdf5IO<ComponentTs<Hdf5IO<ComponentTs...> >...>::save;
464 // };
465 
466 std::vector<std::vector<ScanImage> > HDF5IO::getRawCamData(bool load_image_data)
467 {
468  std::vector<std::vector<ScanImage> > ret;
469 
470  if(m_hdf5_file)
471  {
472  std::string groupNamePhotos = "/raw/photos/";
473 
474  if(!exist(groupNamePhotos))
475  {
476  return ret;
477  }
478 
479  HighFive::Group photos_group = getGroup(groupNamePhotos);
480 
481  size_t num_scans = photos_group.getNumberObjects();
482 
483 
484  for (size_t i = 0; i < num_scans; i++)
485  {
486 
487  std::string cur_scan_pos = photos_group.getObjectName(i);
488  HighFive::Group photo_group = getGroup(photos_group, cur_scan_pos);
489 
490  std::vector<ScanImage> cam_data;
491 
492  size_t num_photos = photo_group.getNumberObjects();
493  for(size_t j=0; j< num_photos; j++)
494  {
495  ScanImage cam = getSingleRawCamData(i, j, load_image_data);
496  cam_data.push_back(cam);
497  }
498 
499  ret.push_back(cam_data);
500  }
501 
502  }
503 
504  return ret;
505 }
506 
507 ScanPtr HDF5IO::getSingleRawScan(int nr, bool load_points)
508 {
509  ScanPtr ret(new Scan());
510 
511  if (m_hdf5_file)
512  {
513  char buffer[128];
514  sprintf(buffer, "position_%05d", nr);
515 
516  string nr_str(buffer);
517  std::string groupName = "/raw/scans/" + nr_str;
518  std::string spectralGroupName = "/annotation/" + nr_str;
519 
520  unsigned int dummy;
521  doubleArr fov = getArray<double>(groupName, "fov", dummy);
522  doubleArr res = getArray<double>(groupName, "resolution", dummy);
523  doubleArr pose_estimate = getArray<double>(groupName, "initialPose", dummy);
524  doubleArr registration = getArray<double>(groupName, "finalPose", dummy);
525  floatArr bb = getArray<float>(groupName, "boundingBox", dummy);
526 
527  if (load_points || m_usePreviews)
528  {
529  if (!load_points)
530  {
531  groupName = "/preview/" + nr_str;
532  spectralGroupName = groupName;
533  }
534 
535  floatArr points = getArray<float>(groupName, "points", dummy);
536 
537  if (points)
538  {
539  ret->points = PointBufferPtr(new PointBuffer(points, dummy/3));
540 
541  std::vector<size_t> dim;
542  ucharArr spectral = getArray<unsigned char>(spectralGroupName, "spectral", dim);
543 
544  if (spectral)
545  {
546  ret->points->addUCharChannel(spectral, "spectral_channels", dim[0], dim[1]);
547  ret->points->addIntAtomic(400, "spectral_wavelength_min");
548  ret->points->addIntAtomic(400 + 4 * dim[1], "spectral_wavelength_max");
549  }
550  }
551  }
552 
553  if (fov)
554  {
555  // ret->m_hFieldOfView = fov[0];
556  // ret->m_vFieldOfView = fov[1];
557  }
558 
559  if (res)
560  {
561  ret->hResolution = res[0];
562  ret->vResolution = res[1];
563  }
564 
565  if (registration)
566  {
567  ret->registration = Transformd(registration.get());
568  }
569 
570  if (pose_estimate)
571  {
572  ret->poseEstimation = Transformd(pose_estimate.get());
573  }
574 
575  if (bb)
576  {
577  ret->boundingBox = BoundingBox<BaseVector<float> >(
578  BaseVector<float>(bb[0], bb[1], bb[2]), BaseVector<float>(bb[3], bb[4], bb[5]));
579  }
580 
581  ret->pointsLoaded = load_points;
582  ret->positionNumber = nr;
583 
584  ret->scanRoot = groupName;
585  }
586 
587  return ret;
588 }
589 
590 
591 ScanImage HDF5IO::getSingleRawCamData(int scan_id, int img_id, bool load_image_data)
592 {
593  ScanImage ret;
594 
595  if (m_hdf5_file)
596  {
597  char buffer1[128];
598  sprintf(buffer1, "position_%05d", scan_id);
599  string scan_id_str(buffer1);
600  char buffer2[128];
601  sprintf(buffer2, "photo_%05d", img_id);
602  string img_id_str(buffer2);
603 
604 
605  std::string groupName = "/raw/photos/" + scan_id_str + "/" + img_id_str;
606 
607  HighFive::Group g;
608 
609  try
610  {
611  g = getGroup(groupName);
612  }
613  catch(HighFive::Exception& e)
614  {
615  std::cout << timestamp << "Error getting cam data: "
616  << e.what() << std::endl;
617  throw e;
618  }
619 
620  unsigned int dummy;
621  doubleArr intrinsics_arr = getArray<double>(groupName, "intrinsics", dummy);
622  doubleArr extrinsics_arr = getArray<double>(groupName, "extrinsics", dummy);
623 
624  if(intrinsics_arr)
625  {
626  //ret.camera.setIntrinsics(Intrinsicsd(intrinsics_arr.get()));
627  }
628 
629  if(extrinsics_arr)
630  {
631  //ret.camera.setExtrinsics(Extrinsicsd(extrinsics_arr.get()));
632  }
633 
634  if(load_image_data)
635  {
636  getImage(g, "image", ret.image);
637  }
638 
639  }
640 
641  return ret;
642 }
643 
644 floatArr HDF5IO::getFloatChannelFromRawScan(std::string name, int nr, unsigned int& n, unsigned& w)
645 {
646  floatArr ret;
647 
648  if (m_hdf5_file)
649  {
650  char buffer[128];
651  sprintf(buffer, "pose%05d", nr);
652  string nr_str(buffer);
653 
654  std::string groupName = "/raw_data/" + nr_str;
655 
656  HighFive::Group g = getGroup(groupName);
657 
658  std::vector<size_t> dim;
659  ret = getArray<float>(g, name, dim);
660 
661  if (dim.size() != 2)
662  {
663  throw std::runtime_error(
664  "HDF5IO - getFloatchannelFromRawScan() Error: dim.size() != 2");
665  }
666 
667  n = dim[0];
668  w = dim[1];
669  }
670 
671  return ret;
672 }
673 
674 void HDF5IO::addImage(std::string group, std::string name, cv::Mat& img)
675 {
676  if(m_hdf5_file)
677  {
678  HighFive::Group g = getGroup(group);
679  addImage(g, name, img);
680  }
681 }
682 
683 void HDF5IO::addImage(HighFive::Group& g, std::string datasetName, cv::Mat& img)
684 {
685  int w = img.cols;
686  int h = img.rows;
687  const char* interlace = "INTERLACE_PIXEL";
688 
689  if(img.type() == CV_8U)
690  {
691  // 1 channel image
692  H5IMmake_image_8bit(g.getId(), datasetName.c_str(), w, h, img.data);
693  } else if(img.type() == CV_8UC3) {
694  // 3 channel image
695  H5IMmake_image_24bit(g.getId(), datasetName.c_str(), w, h, interlace, img.data);
696  }
697 
698 }
699 
700 void HDF5IO::getImage(HighFive::Group& g, std::string datasetName, cv::Mat& img)
701 {
702  long long unsigned int w,h,planes;
703  long long int npals;
704  char interlace[256];
705 
706  H5IMget_image_info(g.getId(), datasetName.c_str(), &w, &h, &planes, interlace, &npals);
707 
708  if(planes == 1)
709  {
710  // 1 channel image
711  img = cv::Mat(h, w, CV_8U);
712  } else if(planes == 3) {
713  // 3 channel image
714  img = cv::Mat(h, w, CV_8UC3);
715  }
716 
717  H5IMread_image(g.getId(), datasetName.c_str(), img.data);
718 }
719 
721  std::string name, int nr, size_t n, unsigned w, floatArr data)
722 {
723  try
724  {
725  HighFive::Group g = getGroup("raw/scans");
726  }
727  catch(HighFive::Exception& e)
728  {
729  std::cout << timestamp << "Error adding raw scan data: "
730  << e.what() << std::endl;
731  throw e;
732  }
733 
734  if(data != nullptr && n > 0 && w > 0 && m_hdf5_file)
735  {
736  // Setup group for scan data
737  char buffer[128];
738  sprintf(buffer, "position_%05d", nr);
739  string nr_str(buffer);
740  std::string groupName = "/raw/scans/" + nr_str;
741  std::vector<size_t> dim = {n, w};
742  addArray(groupName, name, dim, data);
743  }
744  else
745  {
746  std::cout << timestamp << "Error adding float channel '" << name
747  << "'to raw scan data" << std::endl;
748  }
749 }
750 
751 // void HDF5IO::addHyperspectralCalibration(int position, const HyperspectralPanorama& calibration)
752 // {
753 // try
754 // {
755 // HighFive::Group g = getGroup("raw/spectral");
756 // }
757 // catch(HighFive::Exception& e)
758 // {
759 // std::cout << timestamp << "Error adding hyperspectral calibration data: "
760 // << e.what() << std::endl;
761 // throw e;
762 // }
763 
764 // // Add calibration values
765 // if(m_hdf5_file)
766 // {
767 // // Setup group for scan data
768 // char buffer[128];
769 // sprintf(buffer, "position_%05d", position);
770 // string nr_str(buffer);
771 // std::string groupName = "/raw/spectral/" + nr_str;
772 
773 // floatArr a(new float[3]);
774 // a[0] = calibration.distortion(1, 0);
775 // a[1] = calibration.distortion(2, 0);
776 // a[2] = calibration.distortion(3, 0);
777 
778 // floatArr rotation(new float[3]);
779 // a[0] = calibration.rotation(1, 0);
780 // a[1] = calibration.rotation(2, 0);
781 // a[2] = calibration.rotation(3, 0);
782 
783 // floatArr origin(new float[3]);
784 // origin[0] = calibration.origin(1, 0);
785 // origin[1] = calibration.origin(2, 0);
786 // origin[2] = calibration.origin(3, 0);
787 
788 // floatArr principal(new float[2]);
789 // principal[0] = calibration.principal(1, 0);
790 // principal[1] = calibration.principal(2, 0);
791 
792 // addArray(groupName, "distortion", 3, a);
793 // addArray(groupName, "rotation", 3, rotation);
794 // addArray(groupName, "origin", 3, origin);
795 // addArray(groupName, "prinzipal", 2, principal);
796 // }
797 // }
798 
799 void HDF5IO::addRawScan(int nr, ScanPtr scan)
800 {
801  try
802  {
803  HighFive::Group g = getGroup("raw/scans");
804  }
805  catch(HighFive::Exception& e)
806  {
807  std::cout << timestamp << "Error adding raw scan data: "
808  << e.what() << std::endl;
809  throw e;
810  }
811 
812  if(m_hdf5_file)
813  {
814  // Check scan data
815  if(scan->points->numPoints())
816  {
817  // Setup group for scan data
818  char buffer[128];
819  sprintf(buffer, "position_%05d", nr);
820  string nr_str(buffer);
821 
822 
823  std::string groupName = "/raw/scans/" + nr_str;
824 
825  // Generate tuples for field of view and resolution parameters
826  floatArr fov(new float[2]);
827  // fov[0] = scan->m_hFieldOfView;
828  // fov[1] = scan->m_vFieldOfView;
829 
830  floatArr res(new float[2]);
831  res[0] = scan->hResolution;
832  res[1] = scan->vResolution;
833 
834  // Generate pose estimation matrix array
835  float* pose_data = new float[16];
836  float* reg_data = new float[16];
837 
838  std::copy(scan->poseEstimation.data(), scan->poseEstimation.data() + 16, pose_data);
839  std::copy(scan->registration.data(), scan->registration.data() + 16, reg_data);
840 
841  floatArr pose_estimate(pose_data);
842  floatArr registration(reg_data);
843 
844  // Generate bounding box representation
845  floatArr bb(new float[6]);
846 
847  auto bb_min = scan->boundingBox.getMin();
848  auto bb_max = scan->boundingBox.getMax();
849  bb[0] = bb_min.x;
850  bb[1] = bb_min.y;
851  bb[2] = bb_min.z;
852 
853  bb[3] = bb_max.x;
854  bb[4] = bb_max.y;
855  bb[5] = bb_max.z;
856 
857  // Testing code to store point data as integers
858 // cout << "Copy float to int..." << endl;
859 // intArray ints(new int[scan->m_points->numPoints() * 3]);
860 // floatArr tmp_pts = scan->m_points->getPointArray();
861 // for(size_t i = 0; i < scan->m_points->numPoints() * 3; i++)
862 // {
863 // ints[i] = (int)tmp_pts[i] * 10000;
864 // }
865 // cout << "Done" << endl;
866 
867 
868  // Add data to group
869  std::vector<size_t> dim = {4,4};
870  std::vector<size_t> scan_dim = {scan->points->numPoints(), 3};
871  addArray(groupName, "fov", 2, fov);
872  addArray(groupName, "resolution", 2, res);
873  addArray(groupName, "initialPose", dim, pose_estimate);
874  addArray(groupName, "finalPose", dim, registration);
875  addArray(groupName, "boundingBox", 6, bb);
876  addArray(groupName, "points", scan_dim, scan->points->getPointArray());
877 
878  // Uncomment this to store interger points
879  // addArray(groupName, "points", scan_dim, ints);
880 
881 
882  // Add spectral annotation channel
883  size_t an;
884  size_t aw;
885  ucharArr spectral = scan->points->getUCharArray("spectral_channels", an, aw);
886 
887  if (spectral)
888  {
889  size_t chunk_w = std::min<size_t>(an, 1000000); // Limit chunk size
890  std::vector<hsize_t> chunk_annotation = {chunk_w, aw};
891  std::vector<size_t> dim_annotation = {an, aw};
892  addArray("/annotation/" + nr_str, "spectral", dim_annotation, chunk_annotation, spectral);
893  }
894 
895  // Add preview data if wanted
896  if (m_usePreviews)
897  {
898  std::string previewGroupName = "/preview/" + nr_str;
899 
900 
901  // Add point preview
902  floatArr points = scan->points->getPointArray();
903  if (points)
904  {
905  size_t numPreview;
906  floatArr previewData = reduceData(points, scan->points->numPoints(), 3, m_previewReductionFactor, &numPreview);
907 
908  std::vector<size_t> previewDim = {numPreview, 3};
909  addArray(previewGroupName, "points", previewDim, previewData);
910  }
911 
912 
913  // Add spectral preview
914  if (spectral)
915  {
916 
917  size_t numPreview;
918  ucharArr previewData = reduceData(spectral, an, aw, m_previewReductionFactor, &numPreview);
919  std::vector<size_t> previewDim = {numPreview, aw};
920  addArray(previewGroupName, "spectral", previewDim, previewData);
921  }
922  }
923  }
924  }
925 }
926 
927 void HDF5IO::addRawCamData( int scan_id, int img_id, ScanImage& cam_data )
928 {
929  if(m_hdf5_file)
930  {
931 
932  char buffer1[128];
933  sprintf(buffer1, "position_%05d", scan_id);
934  string scan_id_str(buffer1);
935 
936  char buffer2[128];
937  sprintf(buffer2, "photo_%05d", img_id);
938  string photo_id_str(buffer2);
939 
940  std::string groupName = "/raw/photos/" + scan_id_str + "/" + photo_id_str;
941 
942  HighFive::Group photo_group;
943 
944  try
945  {
946  photo_group = getGroup(groupName);
947  }
948  catch(HighFive::Exception& e)
949  {
950  std::cout << timestamp << "Error adding raw image data: "
951  << e.what() << std::endl;
952  throw e;
953  }
954 
955  // add image to scan_image_group
956  doubleArr intrinsics_arr(new double[9]);
957  //Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor>>(intrinsics_arr.get()) = cam_data.camera.intrinsics();
958 
959 
960  doubleArr extrinsics_arr(new double[16]);
961  //Eigen::Map<Eigen::Matrix<double, 4, 4, Eigen::RowMajor>>(extrinsics_arr.get()) = cam_data.camera.extrinsics();
962 
963  std::vector<size_t> dim_4 = {4,4};
964  std::vector<size_t> dim_3 = {3,3};
965 
966  std::vector<hsize_t> chunks;
967  for(auto i: dim_4)
968  {
969  chunks.push_back(i);
970  }
971 
972  addArray(photo_group, "intrinsics", dim_4, chunks, intrinsics_arr);
973  addArray(photo_group, "extrinsics", dim_3, chunks, extrinsics_arr);
974  addImage(photo_group, "image", cam_data.image);
975 
976  }
977 }
978 
979 void HDF5IO::addRawDataHeader(std::string description, Matrix4<BaseVector<float>> &referenceFrame)
980 {
981 
982 }
983 
984 std::vector<std::string> HDF5IO::splitGroupNames(const std::string &groupName)
985 {
986  std::vector<std::string> ret;
987 
988  std::string remainder = groupName;
989  size_t delimiter_pos = 0;
990 
991  while ( (delimiter_pos = remainder.find('/', delimiter_pos)) != std::string::npos)
992  {
993  if (delimiter_pos > 0)
994  {
995  ret.push_back(remainder.substr(0, delimiter_pos));
996  }
997 
998  remainder = remainder.substr(delimiter_pos + 1);
999 
1000  delimiter_pos = 0;
1001  }
1002 
1003  if (remainder.size() > 0)
1004  {
1005  ret.push_back(remainder);
1006  }
1007 
1008  return ret;
1009 }
1010 
1011 
1012 HighFive::Group HDF5IO::getGroup(const std::string &groupName, bool create)
1013 {
1014  std::vector<std::string> groupNames = splitGroupNames(groupName);
1015  HighFive::Group cur_grp;
1016 
1017  try
1018  {
1019  cur_grp = m_hdf5_file->getGroup("/");
1020 
1021  for (size_t i = 0; i < groupNames.size(); i++)
1022  {
1023  if (cur_grp.exist(groupNames[i]))
1024  {
1025  cur_grp = cur_grp.getGroup(groupNames[i]);
1026  }
1027  else if (create)
1028  {
1029  cur_grp = cur_grp.createGroup(groupNames[i]);
1030  }
1031  else
1032  {
1033  // Throw exception because a group we searched
1034  // for doesn't exist and create flag was false
1035  throw std::runtime_error("HDF5IO - getGroup(): Groupname '"
1036  + groupNames[i] + "' doesn't exist and create flag is false");
1037  }
1038  }
1039  }
1040  catch(HighFive::Exception& e)
1041  {
1042  std::cout << timestamp
1043  << "Error in getGroup (with group name '"
1044  << groupName << "': " << std::endl;
1045  std::cout << e.what() << std::endl;
1046  throw e;
1047  }
1048 
1049  return cur_grp;
1050 }
1051 
1052 HighFive::Group HDF5IO::getGroup(HighFive::Group& g, const std::string &groupName, bool create)
1053 {
1054  std::vector<std::string> groupNames = splitGroupNames(groupName);
1055  HighFive::Group cur_grp;
1056 
1057  try
1058  {
1059 
1060  for (size_t i = 0; i < groupNames.size(); i++)
1061  {
1062 
1063  if (g.exist(groupNames[i]))
1064  {
1065  cur_grp = g.getGroup(groupNames[i]);
1066  }
1067  else if (create)
1068  {
1069  cur_grp = g.createGroup(groupNames[i]);
1070  }
1071  else
1072  {
1073  // Throw exception because a group we searched
1074  // for doesn't exist and create flag was false
1075  throw std::runtime_error("HDF5IO - getGroup(): Groupname '"
1076  + groupNames[i] + "' doesn't exist and create flag is false");
1077  }
1078  }
1079  }
1080  catch(HighFive::Exception& e)
1081  {
1082  std::cout << timestamp
1083  << "Error in getGroup (with group name '"
1084  << groupName << "': " << std::endl;
1085  std::cout << e.what() << std::endl;
1086  throw e;
1087  }
1088 
1089  return cur_grp;
1090 }
1091 
1092 bool HDF5IO::exist(const std::string &groupName)
1093 {
1094  std::vector<std::string> groupNames = splitGroupNames(groupName);
1095  HighFive::Group cur_grp;
1096 
1097  try
1098  {
1099  cur_grp = m_hdf5_file->getGroup("/");
1100 
1101  for (size_t i = 0; i < groupNames.size(); i++)
1102  {
1103  if (cur_grp.exist(groupNames[i]))
1104  {
1105  if (i < groupNames.size() -1)
1106  {
1107  cur_grp = cur_grp.getGroup(groupNames[i]);
1108  }
1109  }
1110  else
1111  {
1112  return false;
1113  }
1114  }
1115  }
1116  catch (HighFive::Exception& e)
1117  {
1118  std::cout << timestamp
1119  << "Error in exist (with group name '"
1120  << groupName << "': " << std::endl;
1121  std::cout << e.what() << std::endl;
1122  throw e;
1123 
1124  }
1125 
1126  return true;
1127 }
1128 
1129 bool HDF5IO::isGroup(HighFive::Group grp, std::string objName)
1130 {
1131  H5G_stat_t stats;
1132 
1133  if (H5Gget_objinfo(grp.getId(), objName.c_str(), true, &stats) < 0)
1134  {
1135  return false;
1136  }
1137 
1138  if (stats.type == H5G_GROUP)
1139  {
1140  return true;
1141  }
1142 
1143  return false;
1144 }
1145 
1146 boost::optional<HighFive::Group> HDF5IO::getMeshGroup(bool create){
1147  if(!create && !exist(m_mesh_path)){
1148  std::cout << timestamp << " No mesh with the part name \""
1149  << m_part_name << "\" given in the HDF5 file \"" << std::endl;
1150  return boost::none;
1151  }
1152  return getGroup(m_mesh_path);
1153 }
1154 
1155 
1157  auto mesh_opt = getMeshGroup();
1158  if(!mesh_opt) return boost::none;
1159  auto mesh = mesh_opt.get();
1160  if(!mesh.exist(vertices_name))
1161  {
1162  std::cout << timestamp << " Could not find mesh vertices in the given HDF5 file." << std::endl;
1163  return boost::none;
1164  }
1165 
1166  std::vector<size_t >dims;
1167  auto values = getArray<float>(mesh, vertices_name, dims);
1168  return FloatChannel(dims[0], dims[1], values);
1169 }
1170 
1171 
1173  auto mesh_opt = getMeshGroup();
1174  if(!mesh_opt) return boost::none;
1175  auto mesh = mesh_opt.get();
1176  if(!mesh.exist(indices_name))
1177  {
1178  std::cout << timestamp << " Could not find mesh face indices in the given HDF5 file." << std::endl;
1179  return boost::none;
1180  }
1181 
1182  std::vector<size_t >dims;
1183  auto values = getArray<unsigned int>(mesh, indices_name, dims);
1184  return IndexChannel(dims[0], dims[1], values);
1185 }
1186 
1187 bool HDF5IO::addVertices(const FloatChannel& channel){
1188  auto mesh = getMeshGroup(true).get();
1189  std::vector<size_t > dims = {channel.numElements(), channel.width()};
1190  addArray<float>(m_mesh_path, vertices_name, dims, channel.dataPtr());
1191  return true;
1192 }
1193 
1194 bool HDF5IO::addIndices(const IndexChannel& channel){
1195  auto mesh = getMeshGroup(true).get();
1196  std::vector<size_t > dims = {channel.numElements(), channel.width()};
1197  addArray<unsigned int>(m_mesh_path, indices_name, dims, channel.dataPtr());
1198  return true;
1199 }
1200 
1201 
1202 bool HDF5IO::getChannel(const std::string group, const std::string name, FloatChannelOptional& channel){
1203  return getChannel<float>(group, name, channel);
1204 }
1205 
1206 bool HDF5IO::getChannel(const std::string group, const std::string name, IndexChannelOptional& channel){
1207  return getChannel<unsigned int>(group, name, channel);
1208 }
1209 
1210 bool HDF5IO::getChannel(const std::string group, const std::string name, UCharChannelOptional& channel){
1211  return getChannel<unsigned char>(group, name, channel);
1212 }
1213 
1214 bool HDF5IO::addChannel(const std::string group, const std::string name, const FloatChannel& channel){
1215  return addChannel<float>(group, name, channel);
1216 }
1217 
1218 bool HDF5IO::addChannel(const std::string group, const std::string name, const IndexChannel& channel){
1219  return addChannel<unsigned int>(group, name, channel);
1220 }
1221 
1222 bool HDF5IO::addChannel(const std::string group, const std::string name, const UCharChannel& channel){
1223  return addChannel<unsigned char>(group, name, channel);
1224 }
1225 
1226 } // namespace lvr2
lvr2::floatArr
boost::shared_array< float > floatArr
Definition: DataStruct.hpp:133
lvr2::Texture::m_data
unsigned char * m_data
The texture data.
Definition: Texture.hpp:114
lvr2::HDF5IO::getRawScans
std::vector< ScanPtr > getRawScans(bool load_points=true)
Definition: HDF5IO.cpp:414
lvr2::HDF5IO::addVertices
virtual bool addVertices(const FloatChannel &channel_ptr)
Persistence layer interface, Writes the vertices of the mesh to the persistence layer.
Definition: HDF5IO.cpp:1187
lvr2::IndexChannelOptional
IndexChannel::Optional IndexChannelOptional
Definition: Channel.hpp:100
HighFive::File::ReadOnly
static const int ReadOnly
Open flag: Read only access.
Definition: H5File.hpp:30
lvr2::HDF5IO::reduceData
boost::shared_array< T > reduceData(boost::shared_array< T > data, size_t dataCount, size_t dataWidth, unsigned int reductionFactor, size_t *reducedDataCount)
lvr2::UCharChannelOptional
UCharChannel::Optional UCharChannelOptional
Definition: Channel.hpp:96
lvr2::HDF5IO::addRawDataHeader
void addRawDataHeader(std::string description, Matrix4< BaseVector< float >> &referenceFrame)
Definition: HDF5IO.cpp:979
m_usePreviews
bool m_usePreviews
Definition: src/tools/lvr2_hdf5_builder_2/Main.cpp:20
lvr2::HDF5IO::readPointCloud
bool readPointCloud(ModelPtr model_ptr)
Definition: HDF5IO.cpp:146
lvr2::Matrix4
A 4x4 matrix class implementation for use with the provided vertex types.
Definition: Matrix4.hpp:64
lvr2::HDF5IO::write_base_structure
void write_base_structure()
Definition: HDF5IO.cpp:260
m_previewReductionFactor
int m_previewReductionFactor
Definition: src/tools/lvr2_hdf5_builder_2/Main.cpp:21
lvr2::BaseVector< float >
lvr2::HDF5IO::saveMesh
bool saveMesh(ModelPtr model_ptr)
Definition: HDF5IO.cpp:299
HDF5IO.hpp
lvr2::HDF5IO::m_usePreviews
bool m_usePreviews
Definition: HDF5IO.hpp:321
lvr2::indexArray
boost::shared_array< unsigned int > indexArray
Definition: DataStruct.hpp:128
lvr2::HDF5IO::m_part_name
std::string m_part_name
Definition: HDF5IO.hpp:323
lvr2::HDF5IO::addArray
void addArray(std::string groupName, std::string datasetName, unsigned int size, boost::shared_array< T > data)
HighFive::NodeTraits::createGroup
Group createGroup(const std::string &group_name)
create a new group with the name group_name
Definition: H5Node_traits_misc.hpp:97
lvr2::HDF5IO::meshes_group
static const std::string meshes_group
Definition: HDF5IO.hpp:61
lvr2::HDF5IO::m_previewReductionFactor
unsigned int m_previewReductionFactor
Definition: HDF5IO.hpp:322
lvr2::HDF5IO::deleteDataset
bool deleteDataset(const char *name)
deletes a dataset permanently from the hdf file
Definition: HDF5IO.cpp:110
lvr2::Transformd
Transform< double > Transformd
4x4 double precision transformation matrix
Definition: MatrixTypes.hpp:71
lvr2::PointBufferPtr
std::shared_ptr< PointBuffer > PointBufferPtr
Definition: PointBuffer.hpp:130
lvr2::HDF5IO::isGroup
bool isGroup(HighFive::Group grp, std::string objName)
Definition: HDF5IO.cpp:1129
lvr2::HDF5IO::addIndices
virtual bool addIndices(const IndexChannel &channel_ptr)
Persistence layer interface, Writes the face indices of the mesh to the persistence layer.
Definition: HDF5IO.cpp:1194
lvr2::PointBuffer
A class to handle point information with an arbitrarily large number of attribute channels....
Definition: PointBuffer.hpp:51
lvr2::HDF5IO::compress
bool compress()
Definition: HDF5IO.cpp:105
HighFive::Object::getId
hid_t getId() const
getId
Definition: H5Object_misc.hpp:51
lvr2::Model
Definition: Model.hpp:51
lvr2::HDF5IO::splitGroupNames
std::vector< std::string > splitGroupNames(const std::string &groupName)
Definition: HDF5IO.cpp:984
lvr2::HDF5IO::m_hdf5_file
HighFive::File * m_hdf5_file
Definition: HDF5IO.hpp:317
lvr2::HDF5IO::exist
bool exist(const std::string &groupName)
Definition: HDF5IO.cpp:1092
lvr2::FloatChannelOptional
FloatChannel::Optional FloatChannelOptional
Definition: Channel.hpp:88
HighFive::DataSpace::From
static DataSpace From(const ScalarValue &scalar_value)
Definition: H5Dataspace_misc.hpp:130
lvr2::IndexChannel
Channel< unsigned int > IndexChannel
Definition: Channel.hpp:99
HighFive::NodeTraits::getNumberObjects
size_t getNumberObjects() const
return the number of leaf objects of the node / group
Definition: H5Node_traits_misc.hpp:121
lvr2::HDF5IO::addRawCamData
void addRawCamData(int scan_id, int img_id, ScanImage &cam_data)
add recorded image referenced to a scan pose
Definition: HDF5IO.cpp:927
lvr2::Scan
Definition: ScanTypes.hpp:24
lvr2::HDF5IO::getFloatChannelFromRawScan
floatArr getFloatChannelFromRawScan(std::string name, int nr, unsigned int &n, unsigned &w)
Definition: HDF5IO.cpp:644
lvr2::HDF5IO::readMesh
bool readMesh(ModelPtr model_ptr)
Definition: HDF5IO.cpp:191
lvr2::ScanImage::image
cv::Mat image
OpenCV representation.
Definition: ScanTypes.hpp:126
lvr2::HDF5IO::getMeshGroup
boost::optional< HighFive::Group > getMeshGroup(bool create=false)
Definition: HDF5IO.cpp:1146
lvr2::HDF5IO::setPreviewReductionFactor
void setPreviewReductionFactor(const unsigned int factor)
Definition: HDF5IO.cpp:88
HighFive::NodeTraits::getObjectName
std::string getObjectName(size_t index) const
return the name of the object with the given index
Definition: H5Node_traits_misc.hpp:132
lvr2::MeshBuffer
The MeshBuffer Mesh representation for I/O modules.
Definition: MeshBuffer.hpp:41
lvr2::HDF5IO::addFloatChannelToRawScan
void addFloatChannelToRawScan(std::string name, int nr, size_t n, unsigned w, floatArr data)
Definition: HDF5IO.cpp:720
lvr2::HDF5IO::open
bool open(std::string filename, int open_flag)
Definition: HDF5IO.cpp:232
lvr2::HDF5IO::~HDF5IO
virtual ~HDF5IO()
Definition: HDF5IO.cpp:70
lvr2::HDF5IO::getChannel
bool getChannel(const std::string group, const std::string name, boost::optional< AttributeChannel< T >> &channel)
HighFive::Group
Definition: H5Group.hpp:20
lvr2::HDF5IO::getSingleRawCamData
ScanImage getSingleRawCamData(int scan_id, int img_id, bool load_image_data=true)
Definition: HDF5IO.cpp:591
scripts.normalize_multiple.filename
filename
Definition: normalize_multiple.py:60
lvr2::HDF5IO::getSingleRawScan
ScanPtr getSingleRawScan(int nr, bool load_points=true)
Definition: HDF5IO.cpp:507
scripts.create_png.values
values
Definition: create_png.py:26
lvr2::Channel::dataPtr
const DataPtr dataPtr() const
lvr2::timestamp
static Timestamp timestamp
A global time stamp object for program runtime measurement.
Definition: Timestamp.hpp:116
lvr2::HDF5IO::getGroup
HighFive::Group getGroup(const std::string &groupName, bool create=true)
Definition: HDF5IO.cpp:1012
HighFive::NodeTraits::getGroup
Group getGroup(const std::string &group_name) const
open an existing group with the name group_name
Definition: H5Node_traits_misc.hpp:110
lvr2::ScanImage
Definition: ScanTypes.hpp:107
lvr2::HDF5IO::setChunkSize
void setChunkSize(const size_t &size)
Definition: HDF5IO.cpp:83
lvr2::HDF5IO::m_chunkSize
size_t m_chunkSize
Definition: HDF5IO.hpp:320
HighFive::File
File class.
Definition: H5File.hpp:25
lvr2::HDF5IO::m_mesh_path
std::string m_mesh_path
Definition: HDF5IO.hpp:324
lvr2::HDF5IO::getRawCamData
std::vector< std::vector< ScanImage > > getRawCamData(bool load_image_data=true)
Definition: HDF5IO.cpp:466
lvr2::HDF5IO::addRawScan
void addRawScan(int nr, ScanPtr scan)
Definition: HDF5IO.cpp:799
lvr2::BoundingBox
A dynamic bounding box class.
Definition: BoundingBox.hpp:49
lvr2::HDF5IO::addChannel
bool addChannel(const std::string group, const std::string name, const AttributeChannel< T > &channel)
lvr2::Channel< float >
lvr2::HDF5IO::setCompress
void setCompress(bool compress)
Definition: HDF5IO.cpp:78
lvr2::FloatChannel
Channel< float > FloatChannel
Definition: Channel.hpp:87
lvr2::ucharArr
boost::shared_array< unsigned char > ucharArr
Definition: DataStruct.hpp:137
lvr2::HDF5IO::read
virtual ModelPtr read(std::string filename)
Parse the given file and load supported elements.
Definition: HDF5IO.cpp:121
lvr2
Definition: BaseBufferManipulators.hpp:39
lvr2::ModelPtr
std::shared_ptr< Model > ModelPtr
Definition: Model.hpp:80
HighFive::Object::isValid
bool isValid() const
isValid
Definition: H5Object_misc.hpp:47
HighFive::Exception::what
const char * what() const override
get the current exception error message
Definition: H5Exception.hpp:34
HighFive::Exception
Basic HighFive Exception class.
Definition: H5Exception.hpp:23
lvr2::Texture
This class represents a texture.
Definition: Texture.hpp:54
lvr2::Channel::width
size_t width() const
lvr2::HDF5IO::HDF5IO
HDF5IO()
Construct a new HDF5IO object. Do not use this. Only used by ModelFactory.
Definition: HDF5IO.hpp:93
HighFive::NodeTraits::exist
bool exist(const std::string &node_name) const
check a dataset or group exists in the current node / group
Definition: H5Node_traits_misc.hpp:172
lvr2::HDF5IO::setUsePreviews
void setUsePreviews(bool use)
Definition: HDF5IO.cpp:100
lvr2::HDF5IO::addImage
void addImage(std::string groupName, std::string name, cv::Mat &img)
Definition: HDF5IO.cpp:674
HighFive::File::ReadWrite
static const int ReadWrite
Open flag: Read Write access.
Definition: H5File.hpp:32
HighFive::NodeTraits::createDataSet
DataSet createDataSet(const std::string &dataset_name, const DataSpace &space, const DataType &type, const DataSetCreateProps &createProps=DataSetCreateProps(), const DataSetAccessProps &accessProps=DataSetAccessProps())
createDataSet Create a new dataset in the current file of datatype type and of size space
Definition: H5Node_traits_misc.hpp:36
lvr2::HDF5IO::indices_name
static const std::string indices_name
Definition: HDF5IO.hpp:60
mesh
HalfEdgeMesh< Vec > mesh
Definition: src/tools/lvr2_gs_reconstruction/Main.cpp:26
lvr2::HDF5IO::getIndices
virtual IndexChannelOptional getIndices()
Persistence layer interface, Accesses the face indices of the mesh in the persistence layer.
Definition: HDF5IO.cpp:1172
lvr2::doubleArr
boost::shared_array< double > doubleArr
Definition: DataStruct.hpp:134
lvr2::HDF5IO::chunkSize
size_t chunkSize()
Definition: HDF5IO.cpp:116
lvr2::HDF5IO::getImage
Texture getImage(std::string groupName, std::string datasetName)
Definition: HDF5IO.cpp:360
lvr2::HDF5IO::save
virtual void save(std::string filename)
Save the loaded elements to the given file.
Definition: HDF5IO.cpp:282
HighFive::File::Truncate
static const int Truncate
Open flag: Truncate a file if already existing.
Definition: H5File.hpp:34
lvr2::UCharChannel
Channel< unsigned char > UCharChannel
Definition: Channel.hpp:95
lvr2::HDF5IO::getVertices
virtual FloatChannelOptional getVertices()
Persistence layer interface, Accesses the vertices of the mesh in the persistence layer.
Definition: HDF5IO.cpp:1156
lvr2::HDF5IO::m_compress
bool m_compress
Definition: HDF5IO.hpp:319
lvr2::HDF5IO::vertices_name
static const std::string vertices_name
Definition: HDF5IO.hpp:59
lvr2::Channel::numElements
size_t numElements() const
lvr2::ScanPtr
std::shared_ptr< Scan > ScanPtr
Shared pointer to scans.
Definition: ScanTypes.hpp:98


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