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 typedef typename PointMatcher<T>::DataPoints::Labels Labels;
00052
00054 typedef std::pair<int, std::string >LabelAssociationPair;
00055
00058 typedef std::map<std::string, LabelAssociationPair > SublabelAssociationMap;
00059
00060
00061 static SublabelAssociationMap getFeatAssocationMap();
00062 static SublabelAssociationMap getDescAssocationMap();
00063 static bool featSublabelRegistered(const std::string& externalName);
00064 static bool descSublabelRegistered(const std::string& externalName);
00065 static LabelAssociationPair getFeatAssociationPair(const std::string& externalName);
00066 static LabelAssociationPair getDescAssociationPair(const std::string& externalName);
00067
00068 static std::string getColLabel(const Label& label, const int row);
00069
00071 enum PMPropTypes
00072 {
00073 FEATURE,
00074 DESCRIPTOR,
00075 UNSUPPORTED
00076 };
00077
00079 struct SupportedLabel
00080 {
00081 std::string internalName;
00082 std::string externalName;
00083 PMPropTypes type;
00084
00086 SupportedLabel(const std::string& internalName, const std::string& externalName, const PMPropTypes& type);
00087 };
00088
00090 typedef std::vector<SupportedLabel> SupportedLabels;
00091
00095 static const SupportedLabels & getSupportedExternalLabels()
00096 {
00097
00098
00099 const static SupportedLabels labels = boost::assign::list_of<SupportedLabel>
00100 ("x", "x", FEATURE)
00101 ("y", "y", FEATURE)
00102 ("z", "z", FEATURE)
00103 ("pad", "pad", FEATURE)
00104 ("normals", "nx", DESCRIPTOR)
00105 ("normals", "ny", DESCRIPTOR)
00106 ("normals", "nz", DESCRIPTOR)
00107 ("normals", "normal_x", DESCRIPTOR)
00108 ("normals", "normal_y", DESCRIPTOR)
00109 ("normals", "normal_z", DESCRIPTOR)
00110 ("color", "red", DESCRIPTOR)
00111 ("color", "green", DESCRIPTOR)
00112 ("color", "blue", DESCRIPTOR)
00113 ("color", "alpha", DESCRIPTOR)
00114 ("eigValues", "eigValues0", DESCRIPTOR)
00115 ("eigValues", "eigValues1", DESCRIPTOR)
00116 ("eigValues", "eigValues2", DESCRIPTOR)
00117 ("eigVectors", "eigVectors0X", DESCRIPTOR)
00118 ("eigVectors", "eigVectors0Y", DESCRIPTOR)
00119 ("eigVectors", "eigVectors0Z", DESCRIPTOR)
00120 ("eigVectors", "eigVectors1X", DESCRIPTOR)
00121 ("eigVectors", "eigVectors1Y", DESCRIPTOR)
00122 ("eigVectors", "eigVectors1Z", DESCRIPTOR)
00123 ("eigVectors", "eigVectors2X", DESCRIPTOR)
00124 ("eigVectors", "eigVectors2Y", DESCRIPTOR)
00125 ("eigVectors", "eigVectors2Z", DESCRIPTOR)
00126
00127 ;
00128
00129 return labels;
00130 }
00131
00133 class LabelGenerator
00134 {
00135 Labels labels;
00136
00137 public:
00139 void add(std::string internalName);
00140
00142 Labels getLabels() const;
00143 };
00144
00145
00147 static PMPropTypes getPMType(const std::string& externalName);
00148
00149
00150 static DataPoints loadCSV(const std::string& fileName);
00151 static DataPoints loadCSV(std::istream& is);
00152
00153 static void saveCSV(const DataPoints& data, const std::string& fileName);
00154 static void saveCSV(const DataPoints& data, std::ostream& os);
00155
00156
00158 enum SupportedVTKDataTypes
00159 {
00160 POLYDATA,
00161 UNSTRUCTURED_GRID
00162 };
00163
00164 static DataPoints loadVTK(const std::string& fileName);
00165 static DataPoints loadVTK(std::istream& is);
00166
00167 static void saveVTK(const DataPoints& data, const std::string& fileName);
00168
00169
00170 static DataPoints loadPLY(const std::string& fileName);
00171 static DataPoints loadPLY(std::istream& is);
00172
00173 static void savePLY(const DataPoints& data, const std::string& fileName);
00174
00175
00176 static DataPoints loadPCD(const std::string& fileName);
00177 static DataPoints loadPCD(std::istream& is);
00178
00179 static void savePCD(const DataPoints& data, const std::string& fileName);
00180
00182 struct FileInfo
00183 {
00184 typedef Eigen::Matrix<T, 3, 1> Vector3;
00185
00186 std::string readingFileName;
00187 std::string referenceFileName;
00188 std::string configFileName;
00189 TransformationParameters initialTransformation;
00190 TransformationParameters groundTruthTransformation;
00191 Vector3 gravity;
00192
00193 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());
00194 };
00195
00197 struct FileInfoVector: public std::vector<FileInfo>
00198 {
00199 FileInfoVector();
00200 FileInfoVector(const std::string& fileName, std::string dataPath = "", std::string configPath = "");
00201
00202 protected:
00203 std::string localToGlobalFileName(const std::string& path, const std::string& fileName);
00204 bool findTransform(const PointMatcherSupport::CsvElements& data, const std::string& prefix, unsigned dim);
00205 TransformationParameters getTransform(const PointMatcherSupport::CsvElements& data, const std::string& prefix, unsigned dim, unsigned line);
00206 };
00207
00209 struct CsvDescriptor {
00210 std::string name;
00211 unsigned start_col;
00212 unsigned span;
00213 };
00214
00216 static bool plyPropTypeValid (const std::string& type);
00217
00219 struct PLYProperty
00220 {
00221
00222 std::string name;
00223 std::string type;
00224 std::string idx_type;
00225 unsigned pos;
00226 bool is_list;
00227
00228
00229 PMPropTypes pmType;
00230 int pmRowID;
00231
00232
00233 bool is_feature;
00234
00235 PLYProperty() { }
00236
00237
00238 PLYProperty(const std::string& type, const std::string& name, const unsigned pos, const bool is_feature = false);
00239
00240
00241 PLYProperty(const std::string& idx_type, const std::string& type, const std::string& name, const unsigned pos, const bool is_feature = false);
00242
00243 bool operator==(const PLYProperty& other) const;
00244 };
00245
00248 typedef std::map<std::string, std::vector<PLYProperty> > PLYDescPropMap;
00249
00251 typedef std::vector<PLYProperty> PLYProperties;
00252
00254 typedef typename PLYProperties::iterator it_PLYProp;
00255
00257 class PLYElement
00258 {
00259 public:
00260 std::string name;
00261 unsigned num;
00262 unsigned total_props;
00263 unsigned offset;
00264 PLYProperties properties;
00265 unsigned nbFeatures;
00266 unsigned nbDescriptors;
00267
00268
00270
00278 PLYElement(const std::string& name, const unsigned num, const unsigned offset) :
00279 name(name), num(num), total_props(0), offset(offset), nbFeatures(0), nbDescriptors(0) {}
00280
00281 bool supportsProperty(const PLYProperty& prop) const;
00282
00283 void addProperty(PLYProperty& prop);
00284
00285 bool operator==(const PLYElement& other) const;
00286
00287 };
00288
00289
00291 class PLYVertex : public PLYElement
00292 {
00293 public:
00295
00301 PLYVertex(const unsigned num, const unsigned offset) : PLYElement("vertex", num, offset) {}
00302
00303 };
00304
00306 class PLYElementF
00307 {
00308 enum ElementTypes
00309 {
00310 VERTEX,
00311 UNSUPPORTED
00312 };
00313
00314 static ElementTypes getElementType(const std::string& elem_name);
00315 public:
00316 bool elementSupported(const std::string& elem_name);
00317 static PLYElement* createElement(const std::string& elem_name, const int elem_num, const unsigned offset);
00318 };
00319
00321 static std::istream & safeGetLine( std::istream& os, std::string & line);
00322
00323 };
00324
00325
00326 #endif // __POINTMATCHER_IO_H