Go to the documentation of this file.
   40 #include <opencv2/core/core.hpp> 
   41 #include <opencv2/highgui/highgui.hpp> 
   43 #include <H5Tpublic.h> 
   55 class HDF5IO : 
public BaseIO, 
public AttributeMeshIOBase
 
  118     std::vector<ScanPtr> 
getRawScans(
bool load_points = 
true);
 
  120     std::vector<std::vector<ScanImage> > 
getRawCamData(
bool load_image_data = 
true);
 
  123             int nr, 
unsigned int& n, 
unsigned& w);
 
  128             std::string groupName, std::string name, cv::Mat& img);
 
  161             std::string groupName, std::string datasetName,
 
  166             std::string groupName, std::string datasetName,
 
  167             std::vector<size_t>& dim);
 
  171             std::string groupName,
 
  172             std::string datasetName,
 
  174             boost::shared_array<T> data);
 
  178             std::string groupName,
 
  179             std::string datasetName,
 
  180             std::vector<size_t>& dimensions,
 
  181             boost::shared_array<T> data);
 
  185             std::string groupName,
 
  186             std::string datasetName,
 
  187             std::vector<size_t>& dimensions,
 
  189             boost::shared_array<T> data);
 
  217     template <
typename T>
 
  247     template <
typename T>
 
  277     boost::optional<HighFive::Group> 
getMeshGroup(
bool create = 
false);
 
  286             std::string datasetName,
 
  287             std::vector<size_t>& dim,
 
  289             boost::shared_array<T>& data);
 
  297     std::vector<std::string> 
splitGroupNames(
const std::string &groupName);
 
  299     bool exist(
const std::string &groupName);
 
  310     template <
typename T>
 
  311     boost::shared_array<T> 
reduceData(boost::shared_array<T> data,
 
  314             unsigned int reductionFactor,
 
  315             size_t *reducedDataCount);
 
  329 #include "HDF5IO.tcc" 
  
boost::shared_array< float > floatArr
std::vector< ScanPtr > getRawScans(bool load_points=true)
virtual bool addVertices(const FloatChannel &channel_ptr)
Persistence layer interface, Writes the vertices of the mesh to the persistence layer.
IndexChannel::Optional IndexChannelOptional
static const int ReadOnly
Open flag: Read only access.
boost::shared_array< T > reduceData(boost::shared_array< T > data, size_t dataCount, size_t dataWidth, unsigned int reductionFactor, size_t *reducedDataCount)
UCharChannel::Optional UCharChannelOptional
void addRawDataHeader(std::string description, Matrix4< BaseVector< float >> &referenceFrame)
bool readPointCloud(ModelPtr model_ptr)
A 4x4 matrix class implementation for use with the provided vertex types.
void write_base_structure()
bool saveMesh(ModelPtr model_ptr)
BaseHDF5IO::AddFeatures< lvr2::hdf5features::ScanProjectIO, lvr2::hdf5features::ArrayIO > HDF5IO
void addArray(std::string groupName, std::string datasetName, unsigned int size, boost::shared_array< T > data)
static const std::string meshes_group
unsigned int m_previewReductionFactor
bool deleteDataset(const char *name)
deletes a dataset permanently from the hdf file
bool isGroup(HighFive::Group grp, std::string objName)
virtual bool addIndices(const IndexChannel &channel_ptr)
Persistence layer interface, Writes the face indices of the mesh to the persistence layer.
std::vector< std::string > splitGroupNames(const std::string &groupName)
HighFive::File * m_hdf5_file
bool exist(const std::string &groupName)
FloatChannel::Optional FloatChannelOptional
void addRawCamData(int scan_id, int img_id, ScanImage &cam_data)
add recorded image referenced to a scan pose
floatArr getFloatChannelFromRawScan(std::string name, int nr, unsigned int &n, unsigned &w)
bool readMesh(ModelPtr model_ptr)
boost::optional< HighFive::Group > getMeshGroup(bool create=false)
void setPreviewReductionFactor(const unsigned int factor)
void addFloatChannelToRawScan(std::string name, int nr, size_t n, unsigned w, floatArr data)
bool open(std::string filename, int open_flag)
bool getChannel(const std::string group, const std::string name, boost::optional< AttributeChannel< T >> &channel)
ScanImage getSingleRawCamData(int scan_id, int img_id, bool load_image_data=true)
ScanPtr getSingleRawScan(int nr, bool load_points=true)
Datastructures for holding loaded data.
HighFive::Group getGroup(const std::string &groupName, bool create=true)
void setChunkSize(const size_t &size)
std::vector< std::vector< ScanImage > > getRawCamData(bool load_image_data=true)
void addRawScan(int nr, ScanPtr scan)
bool addChannel(const std::string group, const std::string name, const AttributeChannel< T > &channel)
void setCompress(bool compress)
boost::shared_array< T > getArray(std::string groupName, std::string datasetName, unsigned int &size)
virtual ModelPtr read(std::string filename)
Parse the given file and load supported elements.
Base interface for all I/O related classes.
std::shared_ptr< Model > ModelPtr
This class represents a texture.
HDF5IO()
Construct a new HDF5IO object. Do not use this. Only used by ModelFactory.
void setUsePreviews(bool use)
void addImage(std::string groupName, std::string name, cv::Mat &img)
static const int ReadWrite
Open flag: Read Write access.
static const std::string indices_name
virtual IndexChannelOptional getIndices()
Persistence layer interface, Accesses the face indices of the mesh in the persistence layer.
Texture getImage(std::string groupName, std::string datasetName)
virtual void save(std::string filename)
Save the loaded elements to the given file.
virtual FloatChannelOptional getVertices()
Persistence layer interface, Accesses the vertices of the mesh in the persistence layer.
static const std::string vertices_name
std::shared_ptr< Scan > ScanPtr
Shared pointer to scans.
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