IOUtils.hpp
Go to the documentation of this file.
1 
28 #ifndef IOUTILS_HPP
29 #define IOUTILS_HPP
30 
31 #include "lvr2/io/Timestamp.hpp"
32 #include "lvr2/io/Model.hpp"
36 #include "lvr2/types/ScanTypes.hpp"
37 
38 #include <boost/filesystem.hpp>
39 
40 #include <Eigen/Dense>
41 
42 #include <fstream>
43 #include <vector>
44 
45 namespace lvr2
46 {
47 
48 
56 void getPoseFromFile(BaseVector<float>& position, BaseVector<float>& angles, const boost::filesystem::path file);
57 
70  boost::filesystem::path& transfromFile,
71  std::vector<float>& pts,
72  std::vector<float>& nrm);
73 
74 
79 template<typename T>
80 Transform<T> getTransformationFromFile(const boost::filesystem::path& file);
81 
86 template<typename T>
87 Transform<T> getTransformationFromFrames(const boost::filesystem::path& frames);
88 
93 template<typename T>
94 Transform<T> getTransformationFromPose(const boost::filesystem::path& pose);
95 
100 template<typename T>
101 Transform<T> getTransformationFromDat(const boost::filesystem::path& frames);
102 
109 template<typename T>
110 Transform<T> loadFromFile(const boost::filesystem::path& file);
111 
112 
120 size_t countPointsInFile(const boost::filesystem::path& inFile);
121 
128 template<typename T>
129 void writeFrame(const Transform<T>& transform, const boost::filesystem::path& framesOut);
130 
137 void writePose(const BaseVector<float>& position, const BaseVector<float>& angles, const boost::filesystem::path& out);
138 
146 size_t writeModel( ModelPtr model, const boost::filesystem::path& outfile);
147 
148 
149 
161 size_t getReductionFactor(ModelPtr model, size_t targetSize);
162 
175 size_t getReductionFactor(boost::filesystem::path& inFile, size_t targetSize);
176 
187 void writePointsAndNormals(std::vector<float>& p, std::vector<float>& n, std::string outfile);
188 
200 size_t writePointsToStream(ModelPtr model, std::ofstream& out, bool nocolor = false);
201 
209 size_t getNumberOfPointsInPLY(const std::string& filename);
210 
222 
223 
233 PointBufferPtr subSamplePointBuffer(PointBufferPtr src, const std::vector<size_t>& indices);
234 
244 
251 void parseSLAMDirectory(std::string dir, vector<ScanPtr>& scans);
252 
253 } // namespace lvr2
254 
255 #include "IOUtils.tcc"
256 
257 #endif // IOUTILS_HPP
lvr2::transformPointCloudAndAppend
void transformPointCloudAndAppend(PointBufferPtr &buffer, boost::filesystem::path &transfromFile, std::vector< float > &pts, std::vector< float > &nrm)
Transforms the given point buffer according to the transformation stored in transformFile and appends...
Definition: IOUtils.cpp:40
transform
Definition: src/tools/lvr2_transform/Options.cpp:44
lvr2::slamToLVRInPlace
void slamToLVRInPlace(PointBufferPtr src)
Transforms src, which is assumed to be in slam6Ds left-handed coordinate system into our right-handed...
Definition: IOUtils.cpp:452
lvr2::writeModel
size_t writeModel(ModelPtr model, const boost::filesystem::path &outfile)
Writes the given model to the given file.
Definition: IOUtils.cpp:164
lvr2::writePointsToStream
size_t writePointsToStream(ModelPtr model, std::ofstream &out, bool nocolor=false)
Writes the points stored in the given model to the fiven output stream. This function is used to apen...
Definition: IOUtils.cpp:174
lvr2::PointBufferPtr
std::shared_ptr< PointBuffer > PointBufferPtr
Definition: PointBuffer.hpp:130
lvr2::getPoseFromFile
void getPoseFromFile(BaseVector< float > &position, BaseVector< float > &angles, const boost::filesystem::path file)
Loads an Euler representation of from a pose file.
Definition: IOUtils.cpp:285
CoordinateTransform.hpp
lvr2::writeFrame
void writeFrame(const Transform< T > &transform, const boost::filesystem::path &framesOut)
Writes a Eigen transformation into a .frames file.
p
SharedPointer p
Definition: ConvertShared.hpp:42
ScanTypes.hpp
lvr2::countPointsInFile
size_t countPointsInFile(const boost::filesystem::path &inFile)
Counts the number of points (i.e. number of lines) in the given file.
Definition: IOUtils.cpp:132
lvr2::loadFromFile
Transform< T > loadFromFile(const boost::filesystem::path &file)
Reads an Eigen 4x4 matrix from the given file (16 coefficients, row major)
lvr2::getNumberOfPointsInPLY
size_t getNumberOfPointsInPLY(const std::string &filename)
Get the Number Of Points (element points if present, vertex count otherwise) in a PLY file.
Definition: IOUtils.cpp:295
lvr2::getReductionFactor
size_t getReductionFactor(ModelPtr model, size_t targetSize)
Computes the reduction factor for a given target size (number of points) when reducing a point cloud ...
Definition: IOUtils.cpp:202
scripts.normalize_multiple.filename
filename
Definition: normalize_multiple.py:60
MatrixTypes.hpp
lvr2::getTransformationFromPose
Transform< T > getTransformationFromPose(const boost::filesystem::path &pose)
Returns a Eigen 4x4 maxtrix representation of the transformation represented in the given pose file.
Model.hpp
lvr2::getTransformationFromDat
Transform< T > getTransformationFromDat(const boost::filesystem::path &frames)
Returns a Eigen 4x4 maxtrix representation of the transformation represented in the given dat file.
file
FILE * file
Definition: arithmeticencoder.cpp:77
lvr2::parseSLAMDirectory
void parseSLAMDirectory(std::string dir, vector< ScanPtr > &scans)
Reads a directory containing data from slam6d. Represents.
Definition: IOUtils.cpp:476
lvr2
Definition: BaseBufferManipulators.hpp:39
lvr2::ModelPtr
std::shared_ptr< Model > ModelPtr
Definition: Model.hpp:80
Timestamp.hpp
lvr2::writePointsAndNormals
void writePointsAndNormals(std::vector< float > &p, std::vector< float > &n, std::string outfile)
Writes the points and normals (float triples) stored in p and n to the given output file....
Definition: IOUtils.cpp:252
lvr2::getTransformationFromFrames
Transform< T > getTransformationFromFrames(const boost::filesystem::path &frames)
Returns a Eigen 4x4 maxtrix representation of the transformation represented in the given frame file.
lvr2::getTransformationFromFile
Transform< T > getTransformationFromFile(const boost::filesystem::path &file)
Returns a Eigen 4x4 maxtrix representation of the transformation represented in the given file.
lvr2::writePose
void writePose(const BaseVector< float > &position, const BaseVector< float > &angles, const boost::filesystem::path &out)
Writes pose information in Euler representation to the given file.
Definition: IOUtils.cpp:154
lvr2::subSamplePointBuffer
PointBufferPtr subSamplePointBuffer(PointBufferPtr src, const size_t &n)
Computes a random sub-sampling of a point buffer by creating a uniform distribution over all point in...
Definition: IOUtils.cpp:405
TransformUtils.hpp


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