00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef __POINTMATCHER_IO_H
00037 #define __POINTMATCHER_IO_H
00038
00039 #include "PointMatcher.h"
00040
00042 template<typename T>
00043 struct PointMatcherIO
00044 {
00045 typedef typename PointMatcher<T>::Vector Vector;
00046 typedef typename PointMatcher<T>::Matrix Matrix;
00047 typedef typename PointMatcher<T>::DataPoints DataPoints;
00048 typedef typename PointMatcher<T>::TransformationParameters TransformationParameters;
00049 typedef typename PointMatcher<T>::Matrix Parameters;
00050 typedef typename PointMatcher<T>::DataPoints::Label Label;
00051
00053 typedef std::pair<int, std::string >DescAssociationPair;
00054
00057 typedef std::map<std::string, DescAssociationPair > DescAssociationMap;
00058
00059
00060 static DescAssociationMap getDescAssocationMap();
00061 static bool colLabelRegistered(const std::string& colLabel);
00062 static DescAssociationPair getDescAssociationPair(const std::string& colLabel);
00063
00064 static std::string getColLabel(const Label& label, const int row);
00065
00066
00067 static DataPoints loadCSV(const std::string& fileName);
00068 static DataPoints loadCSV(std::istream& is);
00069
00070 static void saveCSV(const DataPoints& data, const std::string& fileName);
00071 static void saveCSV(const DataPoints& data, std::ostream& os);
00072
00073
00075 enum SupportedVTKDataTypes
00076 {
00077 POLYDATA,
00078 UNSTRUCTURED_GRID
00079 };
00080
00081 static DataPoints loadVTK(const std::string& fileName);
00082 static DataPoints loadVTK(std::istream& is);
00083
00084 static void saveVTK(const DataPoints& data, const std::string& fileName);
00085
00086
00087 static DataPoints loadPLY(const std::string& fileName);
00088 static DataPoints loadPLY(std::istream& is);
00089
00090 static void savePLY(const DataPoints& data, const std::string& fileName);
00091
00092
00093 static DataPoints loadPCD(const std::string& fileName);
00094 static DataPoints loadPCD(std::istream& is);
00095
00096 static void savePCD(const DataPoints& data, const std::string& fileName);
00097
00099 struct FileInfo
00100 {
00101 typedef Eigen::Matrix<T, 3, 1> Vector3;
00102
00103 std::string readingFileName;
00104 std::string referenceFileName;
00105 std::string configFileName;
00106 TransformationParameters initialTransformation;
00107 TransformationParameters groundTruthTransformation;
00108 Vector3 gravity;
00109
00110 FileInfo(const std::string& readingPath="", const std::string& referencePath="", const std::string& configFileName="", const TransformationParameters& initialTransformation=TransformationParameters(), const TransformationParameters& groundTruthTransformation=TransformationParameters(), const Vector& grativity=Vector3::Zero());
00111 };
00112
00114 struct FileInfoVector: public std::vector<FileInfo>
00115 {
00116 FileInfoVector();
00117 FileInfoVector(const std::string& fileName, std::string dataPath = "", std::string configPath = "");
00118
00119 protected:
00120 std::string localToGlobalFileName(const std::string& path, const std::string& fileName);
00121 bool findTransform(const PointMatcherSupport::CsvElements& data, const std::string& prefix, unsigned dim);
00122 TransformationParameters getTransform(const PointMatcherSupport::CsvElements& data, const std::string& prefix, unsigned dim, unsigned line);
00123 };
00124
00126 struct CsvDescriptor {
00127 std::string name;
00128 unsigned start_col;
00129 unsigned span;
00130 };
00131
00133 static bool plyPropTypeValid (const std::string& type);
00134
00136 struct PLYProperty
00137 {
00138
00139 std::string name;
00140 std::string type;
00141 std::string idx_type;
00142 unsigned pos;
00143 bool is_list;
00144 bool is_feature;
00145
00146 PLYProperty() { }
00147
00148
00149 PLYProperty(const std::string& type, const std::string& name, const unsigned pos, const bool is_feature = false);
00150
00151
00152 PLYProperty(const std::string& idx_type, const std::string& type, const std::string& name, const unsigned pos, const bool is_feature = false);
00153
00154 bool operator==(const PLYProperty& other) const;
00155 };
00156
00159
00160 typedef std::map<std::string, std::vector<PLYProperty> > PLYDescPropMap;
00161
00163 class PLYElement
00164 {
00165 public:
00166 std::string name;
00167 unsigned num;
00168 unsigned total_props;
00169 unsigned offset;
00170
00172
00180 PLYElement(const std::string& name, const unsigned num, const unsigned offset) :
00181 name(name), num(num), total_props(0), offset(offset) {}
00182
00183 bool supportsProperty(const PLYProperty& prop) const;
00184
00185 void addProperty(PLYProperty& prop);
00186
00187 const std::vector<PLYProperty>& getFeatureProps() const;
00188
00189 const std::vector<PLYProperty>& getDescriptorProps() const;
00190
00191 const PLYDescPropMap& getDescPropMap() const;
00192
00193 size_t getNumSupportedProperties() const;
00194
00195 int getNumFeatures() const;
00196
00197 int getNumDescriptors() const;
00198
00199 int getNumDescProp() const;
00200
00201 bool operator==(const PLYElement& other) const;
00202
00203 protected:
00205 enum PMPropTypes
00206 {
00207 FEATURE,
00208 DESCRIPTOR,
00209 UNSUPPORTED
00210 };
00211
00212 std::vector<PLYProperty> features;
00213 std::vector<PLYProperty> descriptors;
00214 PLYDescPropMap descriptor_map;
00215
00216 virtual PMPropTypes getPMType(const PLYProperty& prop) const = 0;
00217
00218
00219
00220 };
00221
00222
00224 class PLYVertex : public PLYElement
00225 {
00226 public:
00228
00234 PLYVertex(const unsigned num, const unsigned offset) : PLYElement("vertex", num, offset) {}
00235
00236 typename PLYElement::PMPropTypes getPMType(const PLYProperty& prop) const;
00237
00238
00239 };
00240
00242 class PLYElementF
00243 {
00244 enum ElementTypes
00245 {
00246 VERTEX,
00247 UNSUPPORTED
00248 };
00249
00250 static ElementTypes getElementType(const std::string& elem_name);
00251 public:
00252 bool elementSupported(const std::string& elem_name);
00253 static PLYElement* createElement(const std::string& elem_name, const int elem_num, const unsigned offset);
00254 };
00255
00256 };
00257
00258 #endif // __POINTMATCHER_IO_H