IO.h
Go to the documentation of this file.
00001 // kate: replace-tabs off; indent-width 4; indent-mode normal
00002 // vim: ts=4:sw=4:noexpandtab
00003 /*
00004 
00005 Copyright (c) 2010--2012,
00006 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
00007 You can contact the authors at <f dot pomerleau at gmail dot com> and
00008 <stephane at magnenat dot net>
00009 
00010 All rights reserved.
00011 
00012 Redistribution and use in source and binary forms, with or without
00013 modification, are permitted provided that the following conditions are met:
00014  * Redistributions of source code must retain the above copyright
00015       notice, this list of conditions and the following disclaimer.
00016  * Redistributions in binary form must reproduce the above copyright
00017       notice, this list of conditions and the following disclaimer in the
00018       documentation and/or other materials provided with the distribution.
00019  * Neither the name of the <organization> nor the
00020       names of its contributors may be used to endorse or promote products
00021       derived from this software without specific prior written permission.
00022 
00023 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00024 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00025 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00026 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
00027 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00028 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00030 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00031 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00032 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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>::Int64Matrix Int64Matrix; 
00048         typedef typename PointMatcher<T>::DataPoints DataPoints; 
00049         typedef typename PointMatcher<T>::TransformationParameters TransformationParameters; 
00050         typedef typename PointMatcher<T>::Matrix Parameters; 
00051         typedef typename PointMatcher<T>::DataPoints::Label Label; 
00052         typedef typename PointMatcher<T>::DataPoints::Labels Labels; 
00053 
00055         typedef std::pair<int, std::string >LabelAssociationPair;
00056 
00059         typedef std::map<std::string, LabelAssociationPair > SublabelAssociationMap;
00060         
00061         static std::string getColLabel(const Label& label, const int row); 
00062         
00064         enum PMPropTypes
00065                 {
00066                         FEATURE,
00067                         DESCRIPTOR,
00068                         TIME,
00069                         UNSUPPORTED
00070                 };
00071 
00073         struct SupportedLabel
00074         {
00075                 std::string internalName; 
00076                 std::string externalName; 
00077                 PMPropTypes type; 
00078 
00080                 SupportedLabel(const std::string& internalName, const std::string& externalName, const PMPropTypes& type);
00081         };
00082 
00084         typedef std::vector<SupportedLabel> SupportedLabels;
00085 
00087         struct GenericInputHeader
00088         {
00089                 std::string name; 
00090                 unsigned int matrixRowId; 
00091                 PMPropTypes matrixType; 
00092 
00094                 //TODO: move that to .cpp
00095                 GenericInputHeader(const std::string name)
00096                 {
00097                         init(name);
00098                 };
00099 
00100                 GenericInputHeader()
00101                 {
00102                         init("");
00103                 };
00104 
00105                 private:
00106                 void init(std::string name)
00107                 {
00108                         this->name = name;
00109                         this->matrixRowId = 0;
00110                         this->matrixType = UNSUPPORTED;
00111                 };
00112         };
00113 
00117         static const SupportedLabels & getSupportedExternalLabels()
00118         {
00119                 // This table can be read as:
00120                 //   (internalName, externalName, type)
00121                 const static SupportedLabels labels = {
00122                                 {"x", "x", FEATURE},
00123                                 {"y", "y", FEATURE},
00124                                 {"z", "z", FEATURE},
00125                                 {"pad", "pad", FEATURE},
00126                                 //{"internalName", "externalName", FEATURE},
00127                                 {"normals", "nx", DESCRIPTOR},
00128                                 {"normals", "ny", DESCRIPTOR},
00129                                 {"normals", "nz", DESCRIPTOR},
00130                                 {"normals", "normal_x", DESCRIPTOR},
00131                                 {"normals", "normal_y", DESCRIPTOR},
00132                                 {"normals", "normal_z", DESCRIPTOR},
00133                                 {"observationDirections", "observationDirections0", DESCRIPTOR},
00134                                 {"observationDirections", "observationDirections1", DESCRIPTOR},
00135                                 {"observationDirections", "observationDirections2", DESCRIPTOR},
00136                                 {"color", "red", DESCRIPTOR},
00137                                 {"color", "green", DESCRIPTOR},
00138                                 {"color", "blue", DESCRIPTOR},
00139                                 {"color", "alpha", DESCRIPTOR},
00140                                 {"eigValues", "eigValues0", DESCRIPTOR},
00141                                 {"eigValues", "eigValues1", DESCRIPTOR},
00142                                 {"eigValues", "eigValues2", DESCRIPTOR},
00143                                 {"eigVectors", "eigVectors0X", DESCRIPTOR},
00144                                 {"eigVectors", "eigVectors0Y", DESCRIPTOR},
00145                                 {"eigVectors", "eigVectors0Z", DESCRIPTOR},
00146                                 {"eigVectors", "eigVectors1X", DESCRIPTOR},
00147                                 {"eigVectors", "eigVectors1Y", DESCRIPTOR},
00148                                 {"eigVectors", "eigVectors1Z", DESCRIPTOR},
00149                                 {"eigVectors", "eigVectors2X", DESCRIPTOR},
00150                                 {"eigVectors", "eigVectors2Y", DESCRIPTOR},
00151                                 {"eigVectors", "eigVectors2Z", DESCRIPTOR},
00152                                 {"intensity", "intensity", DESCRIPTOR},
00153                                 //{"internalName", "externalName", DESCRIPTOR},
00154                                 {"time", "time", TIME}
00155                                 //{"internalName", "externalName", TIME}
00156                         };
00157 
00158                         return labels;
00159         }
00160 
00162         class LabelGenerator
00163         {
00164                 Labels labels; 
00165 
00166         public:
00168                 void add(const std::string internalName);
00169 
00171                 void add(const std::string internalName, const unsigned int dim);
00172 
00173 
00175                 Labels getLabels() const;
00176         };
00177 
00178 
00180         //static PMPropTypes getPMType(const std::string& externalName); //! Return the type of information specific to a DataPoints based on a sulabel name
00181 
00182         // CSV
00183         static DataPoints loadCSV(const std::string& fileName);
00184         static DataPoints loadCSV(std::istream& is);
00185 
00186         static void saveCSV(const DataPoints& data, const std::string& fileName);
00187         static void saveCSV(const DataPoints& data, std::ostream& os);
00188 
00189         // VTK
00191         enum SupportedVTKDataTypes
00192         {
00193                 POLYDATA,
00194                 UNSTRUCTURED_GRID
00195         };
00196 
00198         struct SplitTime
00199         {
00200                 bool isHigh32Found;
00201                 bool isLow32Found;
00202 
00203                 Eigen::Matrix<unsigned int, Eigen::Dynamic, Eigen::Dynamic> high32;
00205                 Eigen::Matrix<unsigned int, Eigen::Dynamic, Eigen::Dynamic> low32;
00206 
00208                 SplitTime(): isHigh32Found(false), isLow32Found(false){};
00209 
00210         };
00211 
00212         static DataPoints loadVTK(const std::string& fileName);
00213         static DataPoints loadVTK(std::istream& is);
00214 
00215         static void saveVTK(const DataPoints& data, const std::string& fileName, bool binary = false);
00216 
00217         // PLY
00218         static DataPoints loadPLY(const std::string& fileName);
00219         static DataPoints loadPLY(std::istream& is);
00220 
00221         static void savePLY(const DataPoints& data, const std::string& fileName); 
00222 
00223         // PCD
00224         static DataPoints loadPCD(const std::string& fileName);
00225         static DataPoints loadPCD(std::istream& is);
00226 
00227         static void savePCD(const DataPoints& data, const std::string& fileName); 
00228 
00230         struct FileInfo
00231         {
00232                 typedef Eigen::Matrix<T, 3, 1> Vector3; 
00233 
00234                 std::string readingFileName; 
00235                 std::string referenceFileName; 
00236                 std::string configFileName; 
00237                 TransformationParameters initialTransformation; 
00238                 TransformationParameters groundTruthTransformation; 
00239                 Vector3 gravity; 
00240 
00241                 FileInfo(const std::string& readingPath="", const std::string& referencePath="", const std::string& configFileName="", const TransformationParameters& initialTransformation=TransformationParameters(), const TransformationParameters& groundTruthTransformation=TransformationParameters(),  const Vector& gravity=Vector3::Zero());
00242         };
00243 
00245         struct FileInfoVector: public std::vector<FileInfo>
00246         {
00247                 FileInfoVector();
00248                 FileInfoVector(const std::string& fileName, std::string dataPath = "", std::string configPath = "");
00249 
00250         protected:
00251                 std::string localToGlobalFileName(const std::string& path, const std::string& fileName);
00252                 bool findTransform(const PointMatcherSupport::CsvElements& data, const std::string& prefix, unsigned dim);
00253                 TransformationParameters getTransform(const PointMatcherSupport::CsvElements& data, const std::string& prefix, unsigned dim, unsigned line);
00254         };
00255 
00257         struct CsvDescriptor {
00258                 std::string name; 
00259                 unsigned        start_col; 
00260                 unsigned        span; 
00261         };
00262 
00264         static bool plyPropTypeValid (const std::string& type);
00265 
00267         struct PLYProperty
00268         {
00269                 //PLY information:
00270                 std::string name; 
00271                 std::string type; 
00272                 std::string idx_type; 
00273                 unsigned pos; 
00274                 bool is_list; 
00275                 
00276                 //PointMatcher information:
00277                 PMPropTypes pmType; 
00278                 int pmRowID; 
00279 
00280                 PLYProperty() { } 
00281 
00282                 // regular property
00283                 PLYProperty(const std::string& type, const std::string& name, const unsigned pos);
00284 
00285                 // list property
00286                 PLYProperty(const std::string& idx_type, const std::string& type, const std::string& name, const unsigned pos); 
00287 
00288                 bool operator==(const PLYProperty& other) const; 
00289         };
00290 
00293         typedef std::map<std::string, std::vector<PLYProperty> > PLYDescPropMap;
00294         
00296         typedef std::vector<PLYProperty> PLYProperties;
00297 
00299         typedef typename PLYProperties::iterator it_PLYProp;
00300 
00302         class PLYElement
00303         {
00304         public:
00305                 std::string name; 
00306                 unsigned num; 
00307                 unsigned total_props; 
00308                 unsigned offset; 
00309                 PLYProperties properties; 
00310                 unsigned nbFeatures; 
00311                 unsigned nbDescriptors; 
00312 
00313 
00315 
00323                 PLYElement(const std::string& name, const unsigned num, const unsigned offset) :
00324                         name(name), num(num), total_props(0), offset(offset), nbFeatures(0), nbDescriptors(0) {}
00325 
00326                 //bool supportsProperty(const PLYProperty& prop) const; //!< Returns true if property pro is supported by element
00327 
00328                 bool operator==(const PLYElement& other) const; 
00329 
00330         };
00331 
00332 
00334         class PLYVertex : public PLYElement
00335         {
00336         public:
00338 
00344                 PLYVertex(const unsigned num, const unsigned offset) : PLYElement("vertex", num, offset) {}
00345 
00346         };
00347 
00349         class PLYElementF
00350         {
00351                 enum ElementTypes
00352                 {
00353                         VERTEX,
00354                         UNSUPPORTED
00355                 };
00356 
00357                 static ElementTypes getElementType(const std::string& elem_name);
00358         public:
00359                 bool elementSupported(const std::string& elem_name); 
00360                 static PLYElement* createElement(const std::string& elem_name, const int elem_num, const unsigned offset); 
00361         };
00362 
00364         struct PCDproperty
00365         {
00366                 std::string field; 
00367                 unsigned int size; 
00368                 char type; 
00369                 unsigned int count; 
00370                 
00371                 //PointMatcher information:
00372                 PMPropTypes pmType; 
00373                 int pmRowID; 
00374 
00376                 PCDproperty()
00377                 {
00378                         field = "";
00379                         size = 0;
00380                         type = '-';
00381                         count = 1;
00382                         pmType = UNSUPPORTED;
00383                         pmRowID = -1;
00384                 };
00385         };
00386 
00388         struct PCDheader
00389         {
00390                 std::string version; 
00391                 std::vector<PCDproperty> properties; 
00392                 unsigned int width; 
00393                 unsigned int height; 
00394                 Eigen::Matrix<T, 7, 1> viewPoint;  
00395                 unsigned int nbPoints; 
00396                 std::string dataType; 
00397 
00398                 PCDheader()
00399                 {
00400                         version = "-";
00401                         width = 0;
00402                         height = 0;
00403                         viewPoint = Eigen::Matrix<T, 7, 1>::Zero();
00404                         nbPoints = 0;
00405                         dataType = "-";
00406                 };
00407         };
00408 };
00409 
00410 
00411 #endif // __POINTMATCHER_IO_H


libpointmatcher
Author(s):
autogenerated on Thu Jun 20 2019 19:51:31