pointmatcher/IO.cpp
Go to the documentation of this file.
1 // kate: replace-tabs off; indent-width 4; indent-mode normal
2 // vim: ts=4:sw=4:noexpandtab
3 /*
4 
5 Copyright (c) 2010--2012,
6 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
7 You can contact the authors at <f dot pomerleau at gmail dot com> and
8 <stephane at magnenat dot net>
9 
10 All rights reserved.
11 
12 Redistribution and use in source and binary forms, with or without
13 modification, are permitted provided that the following conditions are met:
14  * Redistributions of source code must retain the above copyright
15  notice, this list of conditions and the following disclaimer.
16  * Redistributions in binary form must reproduce the above copyright
17  notice, this list of conditions and the following disclaimer in the
18  documentation and/or other materials provided with the distribution.
19  * Neither the name of the <organization> nor the
20  names of its contributors may be used to endorse or promote products
21  derived from this software without specific prior written permission.
22 
23 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
24 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
25 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
26 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
27 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
28 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
30 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
31 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
32 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
33 
34 */
35 
36 #include "IO.h"
37 #include "IOFunctions.h"
38 #include "InspectorsImpl.h"
39 
40 // For logging
41 #include "PointMatcherPrivate.h"
42 
43 #include <iostream>
44 #include <fstream>
45 #include <stdexcept>
46 #include <ctype.h>
47 #include "boost/algorithm/string.hpp"
48 #include <filesystem>
49 #include "boost/lexical_cast.hpp"
50 #include "boost/foreach.hpp"
51 
52 #ifdef WIN32
53 #define strtok_r strtok_s
54 #endif // WIN32
55 
56 namespace PointMatcherSupport {
57  namespace {
58  const int one = 1;
59  }
60  const bool isBigEndian = *reinterpret_cast<const unsigned char*>(&one) == static_cast<unsigned char>(0);
61  const int oneBigEndian = isBigEndian ? 1 : 1 << 8 * (sizeof(int) - 1);
62 }
63 
64 using namespace std;
65 using namespace PointMatcherSupport;
66 
67 
68 // Tokenize a string, excepted if it begins with a '%' (a comment in CSV)
69 static std::vector<string> csvLineToVector(const char* line)
70 {
71  std::vector<string> parsedLine;
72  char delimiters[] = " \t,;";
73  char *token;
74  char tmpLine[1024];
75  char *brkt = 0;
76  strcpy(tmpLine, line);
77  token = strtok_r(tmpLine, delimiters, &brkt);
78  if(line[0] != '%') // Jump line if it's commented
79  {
80  while (token)
81  {
82  parsedLine.push_back(string(token));
83  token = strtok_r(NULL, delimiters, &brkt);
84  }
85  }
86 
87  return parsedLine;
88 }
89 
90 // Open and parse a CSV file, return the data
92 {
93  validateFile(fileName);
94 
95  ifstream is(fileName.c_str());
96 
97  unsigned elementCount=0;
98  std::map<string, unsigned> keywordCols;
100 
101  bool firstLine(true);
102  unsigned lineCount=0;
103 
104  string line;
105  while (safeGetLine(is, line))
106  {
107 
108  if(firstLine)
109  {
110  std::vector<string> header = csvLineToVector(line.c_str());
111 
112  elementCount = header.size();
113  for(unsigned int i = 0; i < elementCount; i++)
114  {
115  keywordCols[header[i]] = i;
116  }
117 
118  firstLine = false;
119  }
120  else // load the rest of the file
121  {
122  std::vector<string> parsedLine = csvLineToVector(line.c_str());
123  if(parsedLine.size() != elementCount && parsedLine.size() !=0)
124  {
125  stringstream errorMsg;
126  errorMsg << "Error at line " << lineCount+1 << ": expecting " << elementCount << " columns but read " << parsedLine.size() << " elements.";
127  throw runtime_error(errorMsg.str());
128  }
129 
130  for(unsigned int i = 0; i < parsedLine.size(); i++)
131  {
132  for(BOOST_AUTO(it,keywordCols.begin()); it!=keywordCols.end(); it++)
133  {
134  if(i == (*it).second)
135  {
136  data[(*it).first].push_back(parsedLine[i]);
137  }
138  }
139  }
140  }
141 
142  lineCount++;
143  }
144 
145  // Use for debug
146 
147  //for(BOOST_AUTO(it,data.begin()); it!=data.end(); it++)
148  //{
149  // cout << "--------------------------" << endl;
150  // cout << "Header: |" << (*it).first << "|" << endl;
151  // //for(unsigned i=0; i<(*it).second.size(); i++)
152  // //{
153  // // cout << (*it).second[i] << endl;
154  // //}
155  //}
156 
157 
158  return data;
159 }
160 
161 
163 template<typename T>
164 PointMatcherIO<T>::FileInfo::FileInfo(const std::string& readingFileName, const std::string& referenceFileName, const std::string& configFileName, const TransformationParameters& initialTransformation, const TransformationParameters& groundTruthTransformation, const Vector& gravity):
165  readingFileName(readingFileName),
166  referenceFileName(referenceFileName),
167  configFileName(configFileName),
168  initialTransformation(initialTransformation),
169  groundTruthTransformation(groundTruthTransformation),
170  gravity(gravity)
171 {}
172 
173 template struct PointMatcherIO<float>::FileInfo;
174 template struct PointMatcherIO<double>::FileInfo;
175 
176 // Empty constructor
177 template<typename T>
179 {
180 }
181 
183 
196 template<typename T>
198 {
199  if (dataPath.empty())
200  {
201  dataPath = std::filesystem::path(fileName).parent_path().string();
202  }
203  if (configPath.empty())
204  {
205  configPath = std::filesystem::path(fileName).parent_path().string();
206  }
207 
208  const CsvElements data = parseCsvWithHeader(fileName);
209 
210  // Look for transformations
211  const bool found3dInitialTrans(findTransform(data, "iT", 3));
212  bool found2dInitialTrans(findTransform(data, "iT", 2));
213  const bool found3dGroundTruthTrans(findTransform(data, "gT", 3));
214  bool found2dGroundTruthTrans(findTransform(data, "gT", 2));
215  if (found3dInitialTrans)
216  found2dInitialTrans = false;
217  if (found3dGroundTruthTrans)
218  found2dGroundTruthTrans = false;
219 
220  // Check for consistency
221  if (found3dInitialTrans && found2dGroundTruthTrans)
222  throw runtime_error("Initial transformation is in 3D but ground-truth is in 2D");
223  if (found2dInitialTrans && found3dGroundTruthTrans)
224  throw runtime_error("Initial transformation is in 2D but ground-truth is in 3D");
225  CsvElements::const_iterator readingIt(data.find("reading"));
226  if (readingIt == data.end())
227  throw runtime_error("Error transfering CSV to structure: The header should at least contain \"reading\".");
228  CsvElements::const_iterator referenceIt(data.find("reference"));
229  CsvElements::const_iterator configIt(data.find("config"));
230 
231  // Load reading
232  const std::vector<string>& readingFileNames = readingIt->second;
233  const unsigned lineCount = readingFileNames.size();
234  boost::optional<std::vector<string> > referenceFileNames;
235  boost::optional<std::vector<string> > configFileNames;
236  if (referenceIt != data.end())
237  {
238  referenceFileNames = referenceIt->second;
239  assert (referenceFileNames->size() == lineCount);
240  }
241  if (configIt != data.end())
242  {
243  configFileNames = configIt->second;
244  assert (configFileNames->size() == lineCount);
245  }
246 
247  // for every lines
248  for(unsigned line=0; line<lineCount; line++)
249  {
250  FileInfo info;
251 
252  // Files
253  info.readingFileName = localToGlobalFileName(dataPath, readingFileNames[line]);
254  if (referenceFileNames)
255  info.referenceFileName = localToGlobalFileName(dataPath, (*referenceFileNames)[line]);
256  if (configFileNames)
257  info.configFileName = localToGlobalFileName(configPath, (*configFileNames)[line]);
258 
259  // Load transformations
260  if(found3dInitialTrans)
261  info.initialTransformation = getTransform(data, "iT", 3, line);
262  if(found2dInitialTrans)
263  info.initialTransformation = getTransform(data, "iT", 2, line);
264  if(found3dGroundTruthTrans)
265  info.groundTruthTransformation = getTransform(data, "gT", 3, line);
266  if(found2dGroundTruthTrans)
267  info.groundTruthTransformation = getTransform(data, "gT", 2, line);
268 
269  // Build the list
270  this->push_back(info);
271  }
272 
273  // Debug: Print the list
274  /*for(unsigned i=0; i<list.size(); i++)
275  {
276  cout << "\n--------------------------" << endl;
277  cout << "Sequence " << i << ":" << endl;
278  cout << "Reading path: " << list[i].readingFileName << endl;
279  cout << "Reference path: " << list[i].referenceFileName << endl;
280  cout << "Extension: " << list[i].fileExtension << endl;
281  cout << "Tranformation:\n" << list[i].initialTransformation << endl;
282  cout << "Grativity:\n" << list[i].gravity << endl;
283  }
284  */
285 }
286 
288 template<typename T>
290 {
291  std::string globalFileName(fileName);
292  if (!std::filesystem::exists(globalFileName))
293  {
294  const std::filesystem::path globalFilePath(std::filesystem::path(parentPath) / std::filesystem::path(fileName));
295  globalFileName = globalFilePath.string();
296  }
297  validateFile(globalFileName);
298  return globalFileName;
299 }
300 
302 template<typename T>
304 {
305  bool found(true);
306  for(unsigned i=0; i<dim+1; i++)
307  {
308  for(unsigned j=0; j<dim+1; j++)
309  {
310  stringstream transName;
311  transName << prefix << i << j;
312  found = found && (data.find(transName.str()) != data.end());
313  }
314  }
315  return found;
316 }
317 
319 template<typename T>
321 {
322  TransformationParameters transformation(TransformationParameters::Identity(dim+1, dim+1));
323  for(unsigned i=0; i<dim+1; i++)
324  {
325  for(unsigned j=0; j<dim+1; j++)
326  {
327  stringstream transName;
328  transName << prefix << i << j;
329  CsvElements::const_iterator colIt(data.find(transName.str()));
330  const T value = boost::lexical_cast<T> (colIt->second[line]);
331  transformation(i,j) = value;
332  }
333  }
334  return transformation;
335 }
336 
339 
342 {
343  std::filesystem::path fullPath(fileName);
344 
345  ifstream ifs(fileName.c_str());
346  if (!ifs.good() || !std::filesystem::is_regular_file(fullPath))
347  throw runtime_error(string("Cannot open file ") + std::filesystem::absolute(fullPath).generic_string());
348 }
349 
350 
352 template<typename T>
354 {
355  const std::filesystem::path path(fileName);
356  if (path.has_extension())
357  {
358  const string& ext(path.extension().string());
359  if(ext == ".vtk")
360  return PointMatcherIO<T>::loadVTK(fileName);
361  else if(ext == ".csv")
362  return PointMatcherIO<T>::loadCSV(fileName);
363  else if(ext == ".ply")
364  return PointMatcherIO<T>::loadPLY(fileName);
365  else if(ext == ".pcd")
366  return PointMatcherIO<T>::loadPCD(fileName);
367  else
368  throw runtime_error("loadAnyFormat(): Unknown extension \"" + ext + "\" for file \"" + fileName + "\", extension must be either \".vtk\", \".ply\", \".pcd\" or \".csv\"");
369  }
370  else
371  {
372  throw runtime_error("loadAnyFormat(): Missing extension for file \"" + fileName + "\", extension must be either \".vtk\", \".ply\", \".pcd\" or \".csv\"");
373  }
374 }
375 
376 template
378 template
380 
381 
392 template<typename T>
394 {
395  ifstream ifs(fileName.c_str());
396 
397  validateFile(fileName);
398 
399  return loadCSV(ifs);
400 }
401 
402 template<typename T>
403 PointMatcherIO<T>::SupportedLabel::SupportedLabel(const std::string& internalName, const std::string& externalName, const PMPropTypes& type):
404  internalName(internalName),
405  externalName(externalName),
406  type(type)
407 {
408 }
409 
410 
411 // Class LabelGenerator
412 template<typename T>
414 {
415  bool findLabel = false;
416  for(size_t i=0; i<labels.size(); ++i)
417  {
418  if(internalName == labels[i].text)
419  {
420  labels[i].span++;
421  findLabel = true;
422  break;
423  }
424 
425  }
426 
427  if(!findLabel)
428  {
429  labels.push_back(Label(internalName,1));
430  }
431 }
432 
433 template<typename T>
434 void PointMatcherIO<T>::LabelGenerator::add(const std::string internalName, const unsigned int dim)
435 {
436  labels.push_back(Label(internalName, dim));
437 }
438 
439 
440 // Class LabelGenerator
441 template<typename T>
443 {
444  return labels;
445 }
446 
447 template
449 template
451 template <typename T>
452 
453 
455 {
456  std::string externalName;
457  if (label.text == "normals")
458  {
459  if (row == 0)
460  {
461  externalName = "nx";
462  }
463  if (row == 1)
464  {
465  externalName = "ny";
466  }
467  if (row == 2)
468  {
469  externalName = "nz";
470  }
471  }
472  else if (label.text == "color")
473  {
474  if (row == 0)
475  {
476  externalName = "red";
477  }
478  if (row == 1)
479  {
480  externalName = "green";
481  }
482  if (row == 2)
483  {
484  externalName = "blue";
485  }
486  if (row == 3)
487  externalName = "alpha";
488  }
489  else if (label.text == "eigValues")
490  {
491  externalName = "eigValues" + boost::lexical_cast<string>(row);
492  }
493  else if (label.text == "eigVectors")
494  {
495  // format: eigVectors<0-2><X-Z>
496  externalName = "eigVectors" + boost::lexical_cast<string>(row/3);
497 
498  int row_mod = row % 3;
499  if (row_mod == 0)
500  externalName += "X";
501  else if (row_mod == 1)
502  externalName += "Y";
503  else if (row_mod == 2)
504  externalName += "Z";
505  }
506  else if (label.span == 1)
507  {
508  externalName = label.text;
509  }
510  else
511  externalName = label.text + boost::lexical_cast<std::string>(row);
512 
513  return externalName;
514 }
515 
516 
519 template<typename T>
521 {
522  vector<GenericInputHeader> csvHeader;
523  LabelGenerator featLabelGen, descLabelGen, timeLabelGen;
524  Matrix features;
525  Matrix descriptors;
526  Int64Matrix times;
527  unsigned int csvCol = 0;
528  unsigned int csvRow = 0;
529  bool hasHeader(false);
530  bool firstLine(true);
531 
532 
533  //count lines in the file
534  is.unsetf(std::ios_base::skipws);
535  unsigned int line_count = std::count(
536  std::istream_iterator<char>(is),
537  std::istream_iterator<char>(),
538  '\n');
539  //reset the stream
540  is.clear();
541  is.seekg(0, ios::beg);
542 
543  char delimiters[] = " \t,;";
544  char *token;
545  string line;
546  while (safeGetLine(is, line))
547  {
548 
549  // Skip empty lines
550  if(line.empty())
551  break;
552 
553  // Look for text header
554  unsigned int len = strspn(line.c_str(), " ,+-.1234567890Ee");
555  if(len != line.length())
556  {
557  //cout << "Header detected" << endl;
558  hasHeader = true;
559  }
560  else
561  {
562  hasHeader = false;
563  }
564 
565  // Count dimension using first line
566  if(firstLine)
567  {
568  unsigned int dim = 0;
569  char tmpLine[1024]; //FIXME: might be problematic for large file
570  strcpy(tmpLine, line.c_str());
571  char *brkt = 0;
572  token = strtok_r(tmpLine, delimiters, &brkt);
573 
574  //1- BUILD HEADER
575  while (token)
576  {
577  // Load text header
578  if(hasHeader)
579  {
580  csvHeader.push_back(GenericInputHeader(string(token)));
581  }
582  dim++;
583  token = strtok_r(NULL, delimiters, &brkt);
584  }
585 
586  if (!hasHeader)
587  {
588  // Check if it is a simple file with only coordinates
589  if (!(dim == 2 || dim == 3))
590  {
591  int idX=0, idY=0, idZ=0;
592 
593  cout << "WARNING: " << dim << " columns detected. Not obvious which columns to load for x, y or z." << endl;
594  cout << endl << "Enter column ID (starting from 0) for x: ";
595  cin >> idX;
596  cout << "Enter column ID (starting from 0) for y: ";
597  cin >> idY;
598  cout << "Enter column ID (starting from 0, -1 if 2D data) for z: ";
599  cin >> idZ;
600 
601  // Fill with unkown column names
602  for(unsigned int i=0; i<dim; i++)
603  {
604  std::ostringstream os;
605  os << "empty" << i;
606 
607  csvHeader.push_back(GenericInputHeader(os.str()));
608  }
609 
610  // Overwrite with user inputs
611  csvHeader[idX] = GenericInputHeader("x");
612  csvHeader[idY] = GenericInputHeader("y");
613  if(idZ != -1)
614  csvHeader[idZ] = GenericInputHeader("z");
615  }
616  else
617  {
618  // Assume logical order...
619  csvHeader.push_back(GenericInputHeader("x"));
620  csvHeader.push_back(GenericInputHeader("y"));
621  if(dim == 3)
622  csvHeader.push_back(GenericInputHeader("z"));
623  }
624  }
625 
626  //2- PROCESS HEADER
627  // Load known features, descriptors, and time
628  const SupportedLabels externalLabels = getSupportedExternalLabels();
629 
630  // Counters
631  int rowIdFeatures = 0;
632  int rowIdDescriptors = 0;
633  int rowIdTime = 0;
634 
635 
636  // Loop through all known external names (ordered list)
637  for(size_t i=0; i<externalLabels.size(); i++)
638  {
639  const SupportedLabel supLabel = externalLabels[i];
640 
641  for(size_t j=0; j < csvHeader.size(); j++)
642  {
643  if(supLabel.externalName == csvHeader[j].name)
644  {
645  csvHeader[j].matrixType = supLabel.type;
646 
647  switch (supLabel.type)
648  {
649  case FEATURE:
650  csvHeader[j].matrixRowId = rowIdFeatures;
651  featLabelGen.add(supLabel.internalName);
652  rowIdFeatures++;
653  break;
654  case DESCRIPTOR:
655  csvHeader[j].matrixRowId = rowIdDescriptors;
656  descLabelGen.add(supLabel.internalName);
657  rowIdDescriptors++;
658  break;
659  case TIME:
660  csvHeader[j].matrixRowId = rowIdTime;
661  timeLabelGen.add(supLabel.internalName);
662  rowIdTime++;
663  break;
664  default:
665  throw runtime_error(string("CSV parse error: encounter a type different from FEATURE, DESCRIPTOR and TIME. Implementation not supported. See the definition of 'enum PMPropTypes'"));
666  break;
667  }
668 
669  // we stop searching once we have a match
670  break;
671  }
672  }
673  }
674 
675  // loop through the remaining UNSUPPORTED labels and assigned them to a descriptor row
676  for(unsigned int i=0; i<csvHeader.size(); i++)
677  {
678  if(csvHeader[i].matrixType == UNSUPPORTED)
679  {
680  csvHeader[i].matrixType = DESCRIPTOR; // force descriptor
681  csvHeader[i].matrixRowId = rowIdDescriptors;
682  descLabelGen.add(csvHeader[i].name); // keep original name
683  rowIdDescriptors++;
684  }
685  }
686 
687 
688  //3- RESERVE MEMORY
689  if(hasHeader && line_count > 0)
690  line_count--;
691 
692  const unsigned int featDim = featLabelGen.getLabels().totalDim();
693  const unsigned int descDim = descLabelGen.getLabels().totalDim();
694  const unsigned int timeDim = timeLabelGen.getLabels().totalDim();
695  const unsigned int nbPoints = line_count;
696 
697  features = Matrix(featDim, nbPoints);
698  descriptors = Matrix(descDim, nbPoints);
699  times = Int64Matrix(timeDim, nbPoints);
700  }
701 
702 
703  //4- LOAD DATA (this start again from the first line)
704  char* brkt = 0;
705  char line_c[1024];//FIXME: this might be a problem for large files
706  strcpy(line_c,line.c_str());
707  token = strtok_r(line_c, delimiters, &brkt);
708 
709  if(!(hasHeader && firstLine))
710  {
711  // Parse a line
712  csvCol = 0;
713  while (token)
714  {
715  if(csvCol > (csvHeader.size() - 1))
716  {
717  // Error check (too much data)
718  throw runtime_error(
719  (boost::format("CSV parse error: at line %1%, too many elements to parse compare to the header number of columns (col=%2%).") % csvRow % csvHeader.size()).str());
720  }
721 
722  // Alias
723  const int matrixRow = csvHeader[csvCol].matrixRowId;
724  const int matrixCol = csvRow;
725 
726  switch (csvHeader[csvCol].matrixType)
727  {
728  case FEATURE:
729  features(matrixRow, matrixCol) = lexical_cast_scalar_to_string<T>(string(token));
730  break;
731  case DESCRIPTOR:
732  descriptors(matrixRow, matrixCol) = lexical_cast_scalar_to_string<T>(token);
733  break;
734  case TIME:
735  times(matrixRow, matrixCol) = lexical_cast_scalar_to_string<std::int64_t>(token);
736  break;
737  default:
738  throw runtime_error(string("CSV parse error: encounter a type different from FEATURE, DESCRIPTOR and TIME. Implementation not supported. See the definition of 'enum PMPropTypes'"));
739  break;
740 
741  }
742 
743  //fetch next element
744  token = strtok_r(NULL, delimiters, &brkt);
745  csvCol++;
746  }
747 
748 
749  // Error check (not enough data)
750  if(csvCol != (csvHeader.size()))
751  {
752  throw runtime_error(
753  (boost::format("CSV parse error: at line %1%, not enough elements to parse compare to the header number of columns (col=%2%).") % csvRow % csvHeader.size()).str());
754  }
755 
756  csvRow++;
757  }
758 
759  firstLine = false;
760 
761  }
762 
763  // 5- ASSEMBLE FINAL DATAPOINTS
764  DataPoints loadedPoints(features, featLabelGen.getLabels());
765 
766  if (descriptors.rows() > 0)
767  {
768  loadedPoints.descriptors = descriptors;
769  loadedPoints.descriptorLabels = descLabelGen.getLabels();
770  }
771 
772  if(times.rows() > 0)
773  {
774  loadedPoints.times = times;
775  loadedPoints.timeLabels = timeLabelGen.getLabels();
776  }
777 
778  // Ensure homogeous coordinates
779  if(!loadedPoints.featureExists("pad"))
780  {
781  loadedPoints.addFeature("pad", Matrix::Ones(1,features.cols()));
782  }
783 
784  return loadedPoints;
785 }
786 
787 template
789 template
791 
793 template<typename T>
794 void PointMatcher<T>::DataPoints::save(const std::string& fileName, bool binary, unsigned precision) const
795 {
796  const std::filesystem::path path(fileName);
797  if (path.has_extension())
798  {
799  const string& ext(path.extension().string());
800  if (boost::iequals(ext, ".vtk"))
801  return PointMatcherIO<T>::saveVTK(*this, fileName, binary, precision);
802  else if (boost::iequals(ext, ".ply"))
803  return PointMatcherIO<T>::savePLY(*this, fileName, binary, precision);
804 
805  if (binary)
806  throw runtime_error("save(): Binary writing is not supported together with extension \"" + ext + "\". Currently binary writing is only supported with \".vtk\" and \".ply\".");
807 
808  if (boost::iequals(ext, ".csv"))
809  return PointMatcherIO<T>::saveCSV(*this, fileName, precision);
810  else if (boost::iequals(ext, ".pcd"))
811  return PointMatcherIO<T>::savePCD(*this, fileName, precision);
812  else
813  throw runtime_error("save(): Unknown extension \"" + ext + "\" for file \"" + fileName + "\", extension must be either \".vtk\", \".ply\", \".pcd\" or \".csv\"");
814 
815  }
816  else
817  {
818  throw runtime_error("save(): Missing extension for file \"" + fileName + "\", extension must be either \".vtk\", \".ply\", \".pcd\" or \".csv\"");
819  }
820 }
821 
822 template
823 void PointMatcher<float>::DataPoints::save(const std::string& fileName, bool binary, unsigned precision) const;
824 template
825 void PointMatcher<double>::DataPoints::save(const std::string& fileName, bool binary, unsigned precision) const;
826 
828 template<typename T>
829 void PointMatcherIO<T>::saveCSV(const DataPoints& data, const std::string& fileName, unsigned precision)
830 {
831  ofstream ofs(fileName.c_str());
832  if (!ofs.good())
833  throw runtime_error(string("Cannot open file ") + fileName);
834  ofs.precision(precision);
835  saveCSV(data, ofs);
836 }
837 
839 template<typename T>
840 void PointMatcherIO<T>::saveCSV(const DataPoints& data, std::ostream& os)
841 {
842  const int pointCount(data.features.cols());
843  const int dimCount(data.features.rows());
844  const int descDimCount(data.descriptors.rows());
845 
846  if (pointCount == 0)
847  {
848  LOG_WARNING_STREAM( "Warning, no points, doing nothing");
849  return;
850  }
851 
852  // write header
853  for (int i = 0; i < dimCount - 1; i++)
854  {
855  os << data.featureLabels[i].text;
856 
857  if (!((i == (dimCount - 2)) && descDimCount == 0))
858  os << ",";
859  }
860 
861  int n = 0;
862  for (size_t i = 0; i < data.descriptorLabels.size(); i++)
863  {
864  Label lab = data.descriptorLabels[i];
865  for (size_t s = 0; s < lab.span; s++)
866  {
867  os << getColLabel(lab,s);
868  if (n != (descDimCount - 1))
869  os << ",";
870  n++;
871  }
872  }
873 
874  os << "\n";
875 
876  // write points
877  for (int p = 0; p < pointCount; ++p)
878  {
879  for (int i = 0; i < dimCount-1; ++i)
880  {
881  os << data.features(i, p);
882  if(!((i == (dimCount - 2)) && descDimCount == 0))
883  os << " , ";
884  }
885 
886  for (int i = 0; i < descDimCount; i++)
887  {
888  os << data.descriptors(i,p);
889  if (i != (descDimCount - 1))
890  os << ",";
891  }
892  os << "\n";
893  }
894 
895 }
896 
897 template
898 void PointMatcherIO<float>::saveCSV(const DataPoints& data, const std::string& fileName, unsigned precision);
899 template
900 void PointMatcherIO<double>::saveCSV(const DataPoints& data, const std::string& fileName, unsigned precision);
901 
903 template<typename T>
905 {
906  ifstream ifs(fileName.c_str(), std::ios::binary);
907  if (!ifs.good())
908  throw runtime_error(string("Cannot open file ") + fileName);
909  return loadVTK(ifs);
910 }
911 
912 void skipBlock(bool binary, int binarySize, std::istream & is, bool hasSeparateSizeParameter = true){
913  int n;
914  int size;
915  is >> n;
916  if(!is.good()){
917  throw std::runtime_error("File violates the VTK format : parameter 'n' is missing after a field name.");
918  }
919 
920  if(hasSeparateSizeParameter) {
921  is >> size;
922  if(!is.good()){
923  throw std::runtime_error("File violates the VTK format : parameter 'size' is missing after a field name.");
924  }
925  } else {
926  size = n;
927  }
928 
929  std::string line;
930  safeGetLine(is, line); // remove line end after parameters;
931  if(binary){
932  is.seekg(size * binarySize, std::ios_base::cur);
933  } else {
934  for (int p = 0; p < n; p++)
935  {
936  safeGetLine(is, line);
937  }
938  }
939 }
940 
942 template<typename T>
944 {
945  std::map<std::string, SplitTime> labelledSplitTime;
946 
947  DataPoints loadedPoints;
948 
949  // parse header
950  string line;
951  safeGetLine(is, line);
952  if (line.find("# vtk DataFile Version") != 0)
953  throw runtime_error(string("Wrong magic header, found ") + line);
954  safeGetLine(is, line);
955  safeGetLine(is, line);
956 
957  const bool isBinary = (line == "BINARY");
958  if (line != "ASCII"){
959  if(!isBinary){
960  throw runtime_error(string("Wrong file type, expecting ASCII or BINARY, found ") + line);
961  }
962  }
963  safeGetLine(is, line);
964 
965  SupportedVTKDataTypes dataType;
966  if (line == "DATASET POLYDATA")
967  dataType = POLYDATA;
968  else if (line == "DATASET UNSTRUCTURED_GRID")
969  dataType = UNSTRUCTURED_GRID;
970  else
971  throw runtime_error(string("Wrong data type, expecting DATASET POLYDATA, found ") + line);
972 
973 
974  // parse points, descriptors and time
975  string fieldName;
976  string name;
977  int dim = 0;
978  int pointCount = 0;
979  string type;
980 
981  while (is >> fieldName)
982  {
983  // load features
984  if(fieldName == "POINTS")
985  {
986  is >> pointCount;
987  is >> type;
988  safeGetLine(is, line); // remove line end after parameters!
989 
990  if(!(type == "float" || type == "double"))
991  throw runtime_error(string("Field POINTS can only be of type double or float"));
992 
993  Matrix features(4, pointCount);
994  for (int p = 0; p < pointCount; ++p)
995  {
996  readVtkData(type, isBinary, features.template block<3, 1>(0, p), is);
997  features(3, p) = 1.0;
998  }
999  loadedPoints.addFeature("x", features.row(0));
1000  loadedPoints.addFeature("y", features.row(1));
1001  loadedPoints.addFeature("z", features.row(2));
1002  loadedPoints.addFeature("pad", features.row(3));
1003  }
1004 
1006  // Dataset type
1007  // POLYDATA
1008  else if(dataType == POLYDATA && fieldName == "VERTICES")
1009  {
1010  skipBlock(isBinary, 4, is);
1011  }
1012 
1013  else if(dataType == POLYDATA && fieldName == "LINES")
1014  {
1015  skipBlock(isBinary, 4, is);
1016  }
1017 
1018  else if(dataType == POLYDATA && fieldName == "POLYGONS")
1019  {
1020  skipBlock(isBinary, 4, is);
1021  }
1022 
1023  else if(dataType == POLYDATA && fieldName == "TRIANGLE_STRIPS")
1024  {
1025  skipBlock(isBinary, 4, is);
1026  }
1027 
1028  // Unstructure Grid
1029  else if(dataType == UNSTRUCTURED_GRID && fieldName == "CELLS")
1030  {
1031  skipBlock(isBinary, 4, is);
1032  }
1033  else if(dataType == UNSTRUCTURED_GRID && fieldName == "CELL_TYPES")
1034  {
1035  skipBlock(isBinary, 4, is, false); // according to http://www.vtk.org/VTK/img/file-formats.pdf CELL_TYPES only has one parameter (n)
1036  }
1037 
1039  // Point data
1040  else if(fieldName == "POINT_DATA")
1041  {
1042  int descriptorCount;
1043  is >> descriptorCount;
1044  if(pointCount != descriptorCount)
1045  throw runtime_error(string("The size of POINTS is different than POINT_DATA"));
1046  }
1048  // Field data is ignored
1049  else if (fieldName == "FIELD")
1050  {
1051  string fieldDataName;
1052  int fieldDataCount;
1053  is >> fieldDataName >> fieldDataCount;
1054 
1055  for (int f = 0; f < fieldDataCount; f++)
1056  {
1057  int numTuples;
1058  is >> name >> dim >> numTuples >> type;
1059 
1060  if(type == "vtkIdType") // skip that type
1061  {
1062  if(isBinary){
1063  is.seekg(dim * numTuples * 4, std::ios_base::cur);
1064  } else {
1065  int t_val;
1066  for (int t = 0; t < dim * numTuples; t++ )
1067  {
1068  is >> t_val;
1069  }
1070  }
1071  }
1072  else if(!(type == "float" || type == "double"))
1073  throw runtime_error(string("Field " + fieldName + " is " + type + " but can only be of type double or float"));
1074 
1075 
1076  Matrix descriptor(dim, pointCount);
1077  readVtkData(type, isBinary, descriptor.transpose(), is);
1078  loadedPoints.addDescriptor(name, descriptor);
1079  }
1080  }
1081  else if(fieldName == "METADATA") // Skip METADATA block
1082  {
1083  safeGetLine(is, line);
1084  safeGetLine(is, line);
1085  while(!line.empty())
1086  {
1087  safeGetLine(is, line);
1088  }
1089  }
1090  else // Load descriptors or time
1091  {
1092 
1093  // label name
1094  is >> name;
1095 
1096  bool isTimeSec = false;
1097  bool isTimeNsec = false;
1098 
1099 
1100  if(boost::algorithm::ends_with(name, "_splitTime_high32"))
1101  {
1102  isTimeSec = true;
1103  boost::algorithm::erase_last(name, "_splitTime_high32");
1104  }
1105 
1106  if(boost::algorithm::ends_with(name, "_splitTime_low32"))
1107  {
1108  isTimeNsec = true;
1109  boost::algorithm::erase_last(name, "_splitTime_low32");
1110  }
1111 
1112 
1113  bool skipLookupTable = false;
1114  bool isColorScalars = false;
1115  if(fieldName == "SCALARS")
1116  {
1117  dim = 1;
1118  is >> type;
1119  skipLookupTable = true;
1120  }
1121  else if(fieldName == "VECTORS")
1122  {
1123  dim = 3;
1124  is >> type;
1125  }
1126  else if(fieldName == "TENSORS")
1127  {
1128  dim = 9;
1129  is >> type;
1130  }
1131  else if(fieldName == "NORMALS")
1132  {
1133  dim = 3;
1134  is >> type;
1135  }
1136  else if(fieldName == "COLOR_SCALARS")
1137  {
1138  is >> dim;
1139  type = "float";
1140  isColorScalars = true;
1141  }
1142  else
1143  throw runtime_error(string("Unknown field name " + fieldName + ", expecting SCALARS, VECTORS, TENSORS, NORMALS or COLOR_SCALARS."));
1144 
1145 
1146  safeGetLine(is, line); // remove rest of the parameter line including its line end;
1147 
1148 
1149  // Load time data
1150  if(isTimeSec || isTimeNsec)
1151  {
1152  // Skip LOOKUP_TABLE line
1153  if(skipLookupTable)
1154  {
1155  safeGetLine(is, line);
1156  }
1157 
1158  typename std::map<std::string, SplitTime>::iterator it;
1159 
1160  it = labelledSplitTime.find(name);
1161  // reserve memory
1162  if(it == labelledSplitTime.end())
1163  {
1164  SplitTime t;
1165  t.high32 = Eigen::Matrix<unsigned int, Eigen::Dynamic, Eigen::Dynamic> (dim, pointCount);
1166  t.low32 = t.high32;
1167  labelledSplitTime[name] = t;
1168  }
1169 
1170  // Load seconds
1171  if(isTimeSec)
1172  {
1173  assert(labelledSplitTime[name].isHigh32Found == false);
1174  readVtkData(type, isBinary, labelledSplitTime[name].high32.transpose(), is);
1175  labelledSplitTime[name].isHigh32Found = true;
1176  }
1177 
1178  // Load nano seconds
1179  if(isTimeNsec)
1180  {
1181  assert(labelledSplitTime[name].isLow32Found == false);
1182  readVtkData(type, isBinary, labelledSplitTime[name].low32.transpose(), is);
1183  labelledSplitTime[name].isLow32Found = true;
1184  }
1185  }
1186  else
1187  {
1188 
1189  Matrix descriptorData(dim, pointCount);
1190 
1191  if(isColorScalars && isBinary)
1192  {
1193  std::vector<unsigned char> buffer(dim);
1194  for (int i = 0; i < pointCount; ++i){
1195  is.read(reinterpret_cast<char *>(&buffer.front()), dim);
1196  for(int r=0; r < dim; ++r){
1197  descriptorData(r, i) = buffer[r] / static_cast<T>(255.0);
1198  }
1199  }
1200  }
1201  else
1202  {
1203  if(!(type == "float" || type == "double"))
1204  throw runtime_error(string("Field " + fieldName + " is " + type + " but can only be of type double or float."));
1205 
1206  // Skip LOOKUP_TABLE line
1207  if(skipLookupTable)
1208  {
1209  safeGetLine(is, line);
1210  }
1211  readVtkData(type, isBinary, descriptorData.transpose(), is);
1212  }
1213  loadedPoints.addDescriptor(name, descriptorData);
1214  }
1215  }
1216  }
1217 
1218  // Combine time and add to point cloud
1219  typename std::map<std::string, SplitTime>::iterator it;
1220  for(it=labelledSplitTime.begin(); it!=labelledSplitTime.end(); it++)
1221  {
1222  // Confirm that both parts were loaded
1223  if(it->second.isHigh32Found == false)
1224  {
1225  throw runtime_error(string("Missing time field representing the higher 32 bits. Expecting SCALARS with name " + it->first + "_splitTime_high32 in the VTK file."));
1226  }
1227 
1228  if(it->second.isLow32Found == false)
1229  {
1230  throw runtime_error(string("Missing time field representing the lower 32 bits. Expecting SCALARS with name " + it->first + "_splitTime_low32 in the VTK file."));
1231  }
1232 
1233  // Loop through points
1234  Int64Matrix timeData(1,pointCount);
1235  for(int i=0; i<it->second.high32.cols(); i++)
1236  {
1237 
1238  timeData(0,i) = (((std::int64_t) it->second.high32(0,i)) << 32) | ((std::int64_t) it->second.low32(0,i));
1239  }
1240 
1241  loadedPoints.addTime(it->first, timeData);
1242  }
1243 
1244  return loadedPoints;
1245 }
1246 
1247 template
1249 template
1251 
1252 
1254 template<typename T>
1255 void PointMatcherIO<T>::saveVTK(const DataPoints& data, const std::string& fileName, bool binary, unsigned precision)
1256 {
1257  typedef typename InspectorsImpl<T>::VTKFileInspector VTKInspector;
1258 
1260  boost::assign::insert(param) ("baseFileName", "");
1261  boost::assign::insert(param) ("writeBinary", toParam(binary));
1262  boost::assign::insert(param) ("precision", toParam(precision));
1263  VTKInspector vtkInspector(param);
1264  vtkInspector.dumpDataPoints(data, fileName);
1265 }
1266 
1267 
1268 template
1269 void PointMatcherIO<float>::saveVTK(const PointMatcherIO<float>::DataPoints& data, const std::string& fileName, bool binary, unsigned precision);
1270 template
1271 void PointMatcherIO<double>::saveVTK(const PointMatcher<double>::DataPoints& data, const std::string& fileName, bool binary, unsigned precision);
1272 
1281 template<typename T>
1283 {
1284  ifstream ifs(fileName.c_str());
1285  if (!ifs.good())
1286  throw runtime_error(string("Cannot open file ") + fileName);
1287  return loadPLY(ifs);
1288 }
1289 
1290 template
1292 template
1294 
1297 template <typename T>
1299 {
1300  class Elements : public vector<PLYElement*>{
1301  public:
1302  ~Elements(){
1303  for (typename vector<PLYElement*>::const_iterator it = this->begin(); it != this->end(); it++ )
1304  {
1305  delete *it;
1306  }
1307  }
1308  };
1309 
1310  /*
1311  Steps:
1312  1- PARSE PLY HEADER
1313  2- ASSIGN PLY PROPERTIES TO DATAPOINTS ROWS
1314  3- Reserve memory for a DataPoints
1315  4- Parse PLY vertex to appropriate DataPoints cols and rows
1316  5- Assemble final DataPoints
1317 
1318  PLY organisation:
1319 
1320  element 1 [name, size]
1321  - property 1 [type, name]
1322  - property 2
1323  - ...
1324  element 2
1325  -...
1326 
1327  */
1328 
1329 
1331  // 1- PARSE PLY HEADER
1332  bool format_defined = false;
1333  bool header_processed = false;
1334 
1335  Elements elements;
1336  PLYElementF element_f; // factory
1337  PLYElement* current_element = NULL;
1338  bool skip_props = false; // flag to skip properties if element is not supported
1339  unsigned elem_offset = 0; // keep track of line position of elements that are supported
1340  bool is_binary = false;
1341  string line;
1342  safeGetLine(is, line);
1343 
1344  if (line.find("ply") != 0) {
1345  throw runtime_error(string("PLY parse error: wrong magic header, found <") + line + string(">"));
1346  }
1347 
1348  while (!header_processed)
1349  {
1350  if(!safeGetLine(is, line))
1351  throw runtime_error("PLY parse error: reached end of file before end of header definition");
1352 
1353 
1354  if ( line.empty() )
1355  continue;
1356  istringstream stringstream (line);
1357 
1358  string keyword;
1359  stringstream >> keyword;
1360 
1361  // ignore comment
1362  if (keyword == "comment") {
1363  continue;
1364  }
1365 
1366  // We only support ascii and ply version 1.0
1367  if (keyword == "format")
1368  {
1369  if (format_defined)
1370  throw runtime_error("PLY parse error: format already defined");
1371 
1372  string format_str, version_str;
1373  stringstream >> format_str >> version_str;
1374 
1375  if (format_str != "ascii" && format_str != "binary_little_endian" && format_str != "binary_big_endian")
1376  throw runtime_error(string("PLY parse error: format <") + format_str + string("> is not supported"));
1377 
1378  if (format_str == "binary_little_endian")
1379  is_binary = true;
1380  if (format_str == "binary_big_endian")
1381  throw runtime_error(string("PLY parse error: only little endian binary PLY files are currently supported"));
1382  if (version_str != "1.0")
1383  {
1384  throw runtime_error(string("PLY parse error: version <") + version_str + string("> of ply is not supported"));
1385  }
1386 
1387  format_defined = true;
1388 
1389  }
1390  else if (keyword == "element")
1391  {
1392 
1393 
1394  string elem_name, elem_num_s;
1395  stringstream >> elem_name >> elem_num_s;
1396 
1397  unsigned elem_num;
1398  try
1399  {
1400  elem_num = boost::lexical_cast<unsigned>(elem_num_s);
1401  }
1402  catch (boost::bad_lexical_cast&)
1403  {
1404  throw runtime_error(string("PLY parse error: bad number of elements ") + elem_num_s + string(" for element ") + elem_name);
1405  }
1406 
1407  if (element_f.elementSupported(elem_name))
1408  {
1409  // Initialize current element
1410  PLYElement* elem = element_f.createElement(elem_name, elem_num, elem_offset);
1411  current_element = elem;
1412 
1413  // check that element is not already defined
1414  for (typename Elements::const_iterator it = elements.begin(); it != elements.end(); it++ )
1415  {
1416  if (**it == *elem) {
1417  delete elem;
1418  throw runtime_error(string("PLY parse error: element: ") + elem_name + string( "is already defined"));
1419  }
1420  }
1421  elements.push_back(elem);
1422  skip_props = false;
1423  }
1424  else
1425  {
1426  LOG_WARNING_STREAM("PLY parse warning: element " << elem_name << " not supported. Skipping.");
1427  skip_props = true;
1428  }
1429 
1430  elem_offset += elem_num;
1431  }
1432  else if (keyword == "property")
1433  {
1434  if (current_element == NULL)
1435  {
1436  throw runtime_error("PLY parse error: property listed without defining an element");
1437  }
1438 
1439  if (skip_props)
1440  continue;
1441 
1442  string next, prop_type, prop_name;
1443  stringstream >> next;
1444 
1445  // PLY list property
1446  if (next == "list")
1447  {
1448  string prop_idx_type;
1449  stringstream >> prop_idx_type >> prop_type >> prop_name;
1450 
1451  PLYProperty list_prop(prop_idx_type, prop_type, prop_name, current_element->total_props);
1452 
1453  current_element->properties.push_back(list_prop);
1454  }
1455  // PLY regular property
1456  else
1457  {
1458  prop_type = next;
1459  stringstream >> prop_name;
1460  PLYProperty prop(prop_type, prop_name, current_element->total_props);
1461 
1462  current_element->properties.push_back(prop);
1463  }
1464 
1465  current_element->total_props++;
1466  }
1467  else if (keyword == "end_header")
1468  {
1469  if (!format_defined)
1470  {
1471  throw runtime_error(string("PLY parse error: format not defined in header"));
1472  }
1473 
1474  if (elements.size() == 0)
1475  {
1476  throw runtime_error(string("PLY parse error: no elements defined in header"));
1477  }
1478 
1479  header_processed = true;
1480  }
1481  }
1482 
1484  // 2- ASSIGN PLY PROPERTIES TO DATAPOINTS ROWS
1485 
1486  // Fetch vertex
1487  PLYElement* vertex = elements[0];
1488 
1489  if(vertex->name != "vertex")
1490  {
1491  throw runtime_error(string("PLY parse error: vertex should be the first element defined."));
1492  }
1493 
1494  // Fetch known features and descriptors
1495  const SupportedLabels & externalLabels = getSupportedExternalLabels();
1496 
1497  int rowIdFeatures = 0;
1498  int rowIdDescriptors = 0;
1499  int rowIdTime= 0;
1500 
1501  LabelGenerator featLabelGen, descLabelGen, timeLabelGen;
1502 
1503 
1504  // Loop through all known external names (ordered list)
1505  for(size_t i=0; i<externalLabels.size(); i++)
1506  {
1507  const SupportedLabel & supLabel = externalLabels[i];
1508 
1509  //Search if that feature exist
1510  for(it_PLYProp it=vertex->properties.begin(); it!=vertex->properties.end(); ++it)
1511  {
1512 
1513  if(supLabel.externalName == it->name)
1514  {
1515  it->pmType = supLabel.type;
1516 
1517  // Assign rowId in that order
1518  switch (supLabel.type)
1519  {
1520  case FEATURE:
1521  it->pmRowID = rowIdFeatures;
1522  featLabelGen.add(supLabel.internalName);
1523  rowIdFeatures++;
1524  break;
1525  case DESCRIPTOR:
1526  it->pmRowID = rowIdDescriptors;
1527  descLabelGen.add(supLabel.internalName);
1528  rowIdDescriptors++;
1529  break;
1530  case TIME:
1531  it->pmRowID = rowIdTime;
1532  timeLabelGen.add(supLabel.internalName);
1533  rowIdTime++;
1534  break;
1535  default:
1536  throw runtime_error(string("PLY Implementation Error: encounter a type different from FEATURE, DESCRIPTOR and TIME. Implementation not supported. See the definition of 'enum PMPropTypes'"));
1537  }
1538 
1539  // we stop searching once we have a match
1540  break;
1541  }
1542  }
1543  }
1544 
1545  // loop through the remaining UNSUPPORTED labels and assigned them to a single descriptor row
1546  for(it_PLYProp it=vertex->properties.begin(); it!=vertex->properties.end(); ++it)
1547  {
1548  if(it->pmType == UNSUPPORTED)
1549  {
1550  it->pmType = DESCRIPTOR; // force descriptor
1551  it->pmRowID = rowIdDescriptors;
1552  descLabelGen.add(it->name); // keep original name
1553  rowIdDescriptors++;
1554  }
1555  }
1556 
1558  // 3- RESERVE DATAPOINTS MEMORY
1559 
1560  const unsigned int featDim = featLabelGen.getLabels().totalDim();
1561  const unsigned int descDim = descLabelGen.getLabels().totalDim();
1562  const unsigned int timeDim = timeLabelGen.getLabels().totalDim();
1563  const unsigned int nbPoints = vertex->num;
1564 
1565  Matrix features = Matrix(featDim, nbPoints);
1566  Matrix descriptors = Matrix(descDim, nbPoints);
1567  Int64Matrix times = Int64Matrix(timeDim, nbPoints);
1568 
1569 
1571  // 4- PARSE PLY DATA (vertex)
1572  const int nbProp = vertex->total_props;
1573  const int nbValues = nbPoints*nbProp;
1574  int propID = 0;
1575  int col = 0;
1576  for(int i=0; i<nbValues; i++)
1577  {
1578  T value;
1579  if (is_binary)
1580  {
1581  switch(vertex->properties[propID].type)
1582  {
1584  {
1585  int8_t temp;
1586  is.read(reinterpret_cast<char*>(&temp), sizeof(int8_t));
1587  value = static_cast<T>(temp);
1588  break;
1589  }
1591  {
1592  uint8_t temp;
1593  is.read(reinterpret_cast<char*>(&temp), sizeof(uint8_t));
1594  value = static_cast<T>(temp);
1595  break;
1596  }
1598  {
1599  int16_t temp;
1600  is.read(reinterpret_cast<char*>(&temp), sizeof(int16_t));
1601  value = static_cast<T>(temp);
1602  break;
1603  }
1605  {
1606  uint16_t temp;
1607  is.read(reinterpret_cast<char*>(&temp), sizeof(uint16_t));
1608  value = static_cast<T>(temp);
1609  break;
1610  }
1612  {
1613  // TODO what happens if T is float and we overflow?
1614  int32_t temp;
1615  is.read(reinterpret_cast<char*>(&temp), sizeof(int32_t));
1616  value = static_cast<T>(temp);
1617  break;
1618  }
1620  {
1621  // TODO what happens if T is float and we overflow?
1622  uint32_t temp;
1623  is.read(reinterpret_cast<char*>(&temp), sizeof(uint32_t));
1624  value = static_cast<T>(temp);
1625  break;
1626  }
1628  {
1629  float temp;
1630  is.read(reinterpret_cast<char*>(&temp), sizeof(float));
1631  value = static_cast<T>(temp); // Directly assign if T is float, or cast if T is double
1632  break;
1633  }
1635  {
1636  // TODO what happens if T is float and we read a double?
1637  double temp;
1638  is.read(reinterpret_cast<char*>(&temp), sizeof(double));
1639  value = static_cast<T>(temp); // Directly assign if T is double, or cast if T is float
1640  break;
1641  }
1642  default:
1643  {
1644  throw runtime_error(
1645  (boost::format("Unsupported data type in binary mode %1%.") % static_cast<int>(vertex->properties[propID].type)).str());
1646  }
1647  }
1648  }
1649  if ((is_binary && !is) || (!is_binary && !(is >> value)))
1650  {
1651  throw runtime_error(
1652  (boost::format("PLY parse error: expected %1% values (%2% points with %3% properties) but only found %4% values.") % nbValues % nbPoints % nbProp %
1653  i).str());
1654  }
1655  else
1656  {
1657  const int row = vertex->properties[propID].pmRowID;
1658  const PMPropTypes type = vertex->properties[propID].pmType;
1659 
1660  // rescale color from [0,255] to [0, 1[
1661  // FIXME: do we need that?
1662  if(vertex->properties[propID].name == "red" || vertex->properties[propID].name == "green" || vertex->properties[propID].name == "blue" ||
1663  vertex->properties[propID].name == "alpha")
1664  {
1665  value /= 255.0;
1666  }
1667 
1668  switch (type)
1669  {
1670  case FEATURE:
1671  features(row, col) = value;
1672  break;
1673  case DESCRIPTOR:
1674  descriptors(row, col) = value;
1675  break;
1676  case TIME:
1677  times(row, col) = value;
1678  break;
1679  case UNSUPPORTED:
1680  throw runtime_error("Implementation error in loadPLY(). This should not throw.");
1681  break;
1682  }
1683 
1684  ++propID;
1685 
1686  if(propID >= nbProp)
1687  {
1688  propID = 0;
1689  ++col;
1690  }
1691  }
1692  }
1693 
1695  // 5- ASSEMBLE FINAL DATAPOINTS
1696 
1697  DataPoints loadedPoints(features, featLabelGen.getLabels());
1698 
1699  if (descriptors.rows() > 0)
1700  {
1701  loadedPoints.descriptors = descriptors;
1702  loadedPoints.descriptorLabels = descLabelGen.getLabels();
1703  }
1704 
1705  if(times.rows() > 0)
1706  {
1707  loadedPoints.times = times;
1708  loadedPoints.timeLabels = timeLabelGen.getLabels();
1709  }
1710 
1711  // Ensure homogeneous coordinates
1712  if(!loadedPoints.featureExists("pad"))
1713  {
1714  loadedPoints.addFeature("pad", Matrix::Ones(1,features.cols()));
1715  }
1716 
1717  return loadedPoints;
1718 
1719 }
1720 
1721 template<typename T>
1723  const std::string& fileName, bool binary, unsigned precision)
1724 {
1725  //typedef typename DataPoints::Labels Labels;
1726 
1727  ofstream ofs(fileName.c_str());
1728  if (!ofs.good())
1729  throw runtime_error(string("Cannot open file ") + fileName);
1730 
1731  ofs.precision(precision);
1732  const int pointCount(data.features.cols());
1733  const int featCount(data.features.rows());
1734  const int descRows(data.descriptors.rows());
1735 
1736 
1737  if (pointCount == 0)
1738  {
1739  LOG_WARNING_STREAM("Warning, no points, doing nothing");
1740  return;
1741  }
1742 
1743  if (binary)
1744  ofs << "ply\n" <<"format binary_little_endian 1.0\n";
1745  else
1746  ofs << "ply\n" <<"format ascii 1.0\n";
1747 
1748  ofs << "comment File created with libpointmatcher\n";
1749  ofs << "element vertex " << pointCount << "\n";
1750  std::string dataType;
1751 
1752  using ValueType = typename std::conditional<std::is_same<T, float>::value, float, double>::type;
1753  if (std::is_same<ValueType, float>::value)
1754  dataType = "float";
1755  else
1756  dataType = "double";
1757 
1758  for (int f=0; f <(featCount-1); f++)
1759  {
1760  ofs << "property " << dataType << " " << data.featureLabels[f].text << "\n";
1761  }
1762 
1763  for (size_t i = 0; i < data.descriptorLabels.size(); i++)
1764  {
1765  Label lab = data.descriptorLabels[i];
1766  for (size_t s = 0; s < lab.span; s++)
1767  {
1768  std::string label = getColLabel(lab,s);
1769  if (label == "red" || label == "green" || label == "blue" || label == "alpha")
1770  ofs << "property uchar " << label << "\n";
1771  else
1772  ofs << "property " << dataType << " " << label << "\n";
1773  }
1774  }
1775 
1776  ofs << "end_header\n";
1777 
1778  // write points
1779  for (int p = 0; p < pointCount; ++p)
1780  {
1781  for (int f = 0; f < featCount - 1; ++f)
1782  {
1783  if (binary)
1784  {
1785  ofs.write(reinterpret_cast<const char*>(&data.features(f, p)), sizeof(T));
1786  }
1787  else
1788  {
1789  ofs << data.features(f, p);
1790  if(!(f == featCount - 2 && descRows == 0))
1791  ofs << " ";
1792  }
1793  }
1794 
1795  bool datawithColor = data.descriptorExists("color");
1796  int colorStartingRow = data.getDescriptorStartingRow("color");
1797  int colorEndRow = colorStartingRow + data.getDescriptorDimension("color");
1798  for (int d = 0; d < descRows; ++d)
1799  {
1800  if (datawithColor && d >= colorStartingRow && d < colorEndRow) {
1801  if (binary)
1802  {
1803  char value = static_cast<char>(data.descriptors(d, p) * 255.0);
1804  ofs.write(reinterpret_cast<const char*>(&value), sizeof(char));
1805  }
1806  else
1807  ofs << static_cast<unsigned>(data.descriptors(d, p) * 255.0);
1808  } else {
1809  if (binary)
1810  ofs.write(reinterpret_cast<const char*>(&data.descriptors(d, p)), sizeof(T));
1811  else
1812  ofs << data.descriptors(d, p);
1813  }
1814  if(d != descRows-1 && !binary)
1815  ofs << " ";
1816  }
1817  if(!binary)
1818  ofs << "\n";
1819  }
1820 
1821  ofs.close();
1822 }
1823 
1824 template
1825 void PointMatcherIO<float>::savePLY(const DataPoints& data, const std::string& fileName, bool binary, unsigned precision);
1826 template
1827 void PointMatcherIO<double>::savePLY(const DataPoints& data, const std::string& fileName, bool binary, unsigned precision);
1828 
1830 template<typename T>
1832  const std::string& name, const unsigned pos) :
1833  name(name),
1834  pos(pos)
1835 {
1836  if (plyPropTypeValid(type))
1837  {
1838  this->type = get_type_from_string(type);
1839  is_list = false;
1840  }
1841  else
1842  {
1843  throw std::runtime_error(
1844  std::string("PLY parse error: property type ") + type
1845  + std::string(" for property ") + name
1846  + std::string(" is invalid"));
1847  }
1848 
1849  pmType = UNSUPPORTED;
1850  pmRowID = -1;
1851 
1852 }
1853 
1855 template<typename T>
1857  const std::string& type, const std::string& name, const unsigned pos) :
1858  name(name),
1859  idx_type(idx_type),
1860  pos(pos)
1861 {
1863  {
1864  this->type = get_type_from_string(type);
1865  is_list = true;
1866  }
1867  else
1868  {
1869  throw std::runtime_error(
1870  std::string("PLY parse error: property list type ") + idx_type
1871  + std::string(" ") + type
1872  + std::string(" for property ") + name
1873  + std::string(" is invalid"));
1874  }
1875 
1876  pmType = UNSUPPORTED;
1877  pmRowID = -1;
1878 }
1879 
1880 template
1882 template
1884 
1885 template
1887 template
1889 
1890 
1891 template <typename T>
1893 {
1894  string lc = elem_name;
1895  boost::algorithm::to_lower(lc);
1896  if (lc == "vertex")
1897  {
1898  return VERTEX;
1899  }
1900  else
1901  {
1902  return UNSUPPORTED;
1903  }
1904 }
1905 
1906 
1907 template <typename T>
1909 {
1910  return getElementType(elem_name) != UNSUPPORTED;
1911 }
1912 
1913 
1914 template<typename T>
1916  const std::string& elem_name, const int elem_num, const unsigned offset) {
1917  ElementTypes type = getElementType(elem_name);
1918  if (type == VERTEX)
1919  return new PLYVertex(elem_num, offset);
1920  else
1921  return NULL;
1922 }
1923 
1924 
1925 template<typename T>
1927  return (type == "char" || type == "uchar" || type == "short"
1928  || type == "ushort" || type == "int" || type == "uint"
1929  || type == "float" || type == "double");
1930 }
1931 
1932 
1933 // Explicitly instatiating the template for PLYElement, PLYProperty and PLYElementF
1934 // class functions to fix Python bindings import, which otherwise complains about a missing
1935 // symbol on pypointmatcher import
1938 
1941 
1943  const std::string& elem_name, const int elem_num, const unsigned offset);
1945  const std::string& elem_name, const int elem_num, const unsigned offset);
1946 
1949 
1950 template <typename T>
1952 {
1953  return name == rhs.name;
1954 }
1955 
1956 
1957 template <typename T>
1959 {
1960  return name == rhs.name && type == rhs.type;
1961 }
1962 
1963 
1966 template<typename T>
1967 typename PointMatcherIO<T>::DataPoints PointMatcherIO<T>::loadPCD(const string& fileName) {
1968  ifstream ifs(fileName.c_str());
1969  if (!ifs.good())
1970  throw runtime_error(string("Cannot open file ") + fileName);
1971  return loadPCD(ifs);
1972 }
1973 
1974 
1975 template
1977 template
1979 
1980 
1983 template<typename T>
1985 
1986 
1987  /*
1988  Steps:
1989  1- PARSE PCD HEADER
1990  2- ASSIGN PCD PROPERTIES TO DATAPOINTS ROWS
1991  3- Reserve memory for a DataPoints
1992  4- Parse PCD XXX to appropriate DataPoints cols and rows
1993  5- Assemble final DataPoints
1994 
1995  PCD organisation:
1996 
1997  # .PCD v.7 - Point Cloud Data file format
1998  VERSION number
1999  FIELDS prop1 prop2 prop3 ...
2000  SIZE nbBytes1 nbBytes2 nbBytes3
2001  TYPE type1 type2 type3
2002  COUNT nbDim1 nbDim2 nbDim3
2003  WIDTH w
2004  HEIGHT h
2005  VIEWPOINT 0 0 0 1 0 0 0
2006  POINTS size (should be w*h)
2007  DATA ascii or binary
2008  data1 data2 data3 ...
2009  data1 data2 data3 ...
2010  ...
2011 
2012  */
2013 
2014 
2016  // 1- PARSE PCD HEADER
2017 
2018  size_t lineNum = 0;
2019  PCDheader header;
2020 
2021  string line;
2022  while (safeGetLine(is, line))
2023  {
2024 
2025  // get rid of white spaces before/after
2026  boost::trim (line);
2027 
2028  // ignore comments or empty line
2029  if (line.substr(0,1) == "#" || line == "")
2030  {
2031  lineNum++;
2032  continue;
2033  }
2034 
2035  vector<string> tokens;
2036  boost::split(tokens, line, boost::is_any_of("\t\r "), boost::token_compress_on);
2037 
2038  string pcd_version_str;
2039  if (tokens[0] == "VERSION")
2040  {
2041  header.version = tokens[1];
2042 
2043  if (tokens[1] != "0.7" && tokens[1] != ".7")
2044  throw runtime_error("PCD Parse Error: Only PCD Version 0.7 is supported");
2045  }
2046 
2047  else if (tokens[0] == "FIELDS")
2048  {
2049  header.properties.resize(tokens.size() - 1);
2050 
2051  for (size_t i = 1; i < tokens.size(); i++)
2052  {
2053  header.properties[i-1].field = tokens[i];
2054  }
2055 
2056  }
2057 
2058  else if (tokens[0] == "SIZE")
2059  {
2060  if((tokens.size() - 1) != header.properties.size())
2061  throw runtime_error("PCD Parse Error: number of elements for SIZE must be the same as FIELDS");
2062 
2063  for (size_t i = 1; i < tokens.size(); i++)
2064  {
2065  const unsigned int size = boost::lexical_cast<unsigned int >(tokens[i]);
2066  header.properties[i-1].size = size;
2067  }
2068 
2069  }
2070 
2071  else if (tokens[0] == "TYPE")
2072  {
2073  if((tokens.size() - 1) != header.properties.size())
2074  throw runtime_error("PCD Parse Error: number of elements for TYPE must be the same as FIELDS");
2075 
2076  for (size_t i = 1; i < tokens.size(); i++)
2077  {
2078  const char type = boost::lexical_cast<char>(tokens[i]);
2079  header.properties[i-1].type = type;
2080  if (type != 'I' && type != 'U' && type != 'F')
2081  throw runtime_error("PCD Parse Error: invalid TYPE, it must be 'I', 'U', or 'F'");
2082  }
2083 
2084  }
2085 
2086  else if (tokens[0] == "COUNT")
2087  {
2088 
2089  if((tokens.size() - 1) != header.properties.size())
2090  throw runtime_error("PCD Parse Error: number of elements for COUNT must be the same as FIELDS");
2091 
2092  for (size_t i = 1; i < tokens.size(); i++)
2093  {
2094  const unsigned int count = boost::lexical_cast<unsigned int >(tokens[i]);
2095  header.properties[i-1].count = count;
2096  }
2097 
2098  }
2099 
2100  else if (tokens[0] == "WIDTH")
2101  {
2102  try
2103  {
2104  header.width = boost::lexical_cast<unsigned int >(tokens[1]);
2105  }
2106  catch (boost::bad_lexical_cast&)
2107  {
2108  throw runtime_error("PCD Parse Error: invalid WIDTH");
2109  }
2110 
2111  }
2112 
2113  else if (tokens[0] == "HEIGHT")
2114  {
2115  try
2116  {
2117  header.height= boost::lexical_cast<unsigned int >(tokens[1]);
2118  }
2119  catch (boost::bad_lexical_cast&)
2120  {
2121  throw runtime_error("PCD Parse Error: invalid HEIGHT");
2122  }
2123 
2124  }
2125 
2126  else if (tokens[0] == "VIEWPOINT")
2127  {
2128  if((tokens.size() - 1) != 7 )
2129  throw runtime_error("PCD Parse Error: number of elements for VIEWPOINT must be 7");
2130 
2131  for (size_t i = 1; i < tokens.size(); i++)
2132  {
2133  try
2134  {
2135  header.viewPoint(i-1, 0) = boost::lexical_cast<T>(tokens[i]);
2136  }
2137  catch (boost::bad_lexical_cast&)
2138  {
2139  stringstream ss;
2140  ss << "PCD Parse Error: invalid value(" << tokens[i] << ") of VIEWPOINT";
2141  throw runtime_error(ss.str());
2142  }
2143  }
2144 
2145  }
2146 
2147  else if (tokens[0] == "POINTS")
2148  {
2149  try
2150  {
2151  header.nbPoints = boost::lexical_cast<unsigned int>(tokens[1]);
2152  }
2153  catch (boost::bad_lexical_cast&)
2154  {
2155  stringstream ss;
2156  ss << "PCD Parse Error: the value in the element POINTS (" << tokens[1] << ") could not be cast as unsigned int";
2157  throw runtime_error(ss.str());
2158  }
2159  }
2160 
2161  else if (tokens[0] == "DATA")
2162  {
2163  header.dataType= tokens[1];
2164 
2165  if (header.dataType == "ascii")
2166  {
2167  // DATA is the last element of the header, we exit the loop
2168  break;
2169  }
2170  else if(header.dataType == "binary")
2171  {
2172  throw runtime_error("PCD Implementation Error: the option for DATA binary is not implemented yet");
2173  }
2174  else
2175  {
2176  stringstream ss;
2177  ss << "PCD Parse Error: the value in the element DATA (" << tokens[1] << ") must be ascii or binary";
2178  throw runtime_error(ss.str());
2179  }
2180 
2181  }
2182 
2183  lineNum++;
2184  }
2185  // Extra check for the number of points
2186  if (header.properties.size() == 0)
2187  throw runtime_error("PCD Parse Error: no FIELDS were find in the header");
2188 
2189 
2190  // Extra check for the number of points
2191  if (header.width * header.height != header.nbPoints)
2192  throw runtime_error("PCD Parse Error: POINTS field does not match WIDTH and HEIGHT fields");
2193 
2195  // 2- ASSIGN PCD PROPERTIES TO DATAPOINTS ROWS
2196 
2197  // Fetch known features and descriptors
2198  const SupportedLabels & externalLabels = getSupportedExternalLabels();
2199 
2200  int rowIdFeatures = 0;
2201  int rowIdDescriptors = 0;
2202  int rowIdTime= 0;
2203 
2204  LabelGenerator featLabelGen, descLabelGen, timeLabelGen;
2205 
2206  // Loop through all known external names (ordered list)
2207  for(size_t i=0; i<externalLabels.size(); i++)
2208  {
2209  const SupportedLabel & supLabel = externalLabels[i];
2210 
2211  //Search if that feature exist
2212  for(size_t i=0; i < header.properties.size(); i++)
2213  {
2214  const PCDproperty prop = header.properties[i];
2215 
2216  //TODO: prop.field == "rgb" might be tricky
2217 
2218  if(supLabel.externalName == prop.field)
2219  {
2220  header.properties[i].pmType = supLabel.type;
2221 
2222  // Assign rowId in that order
2223  switch (supLabel.type)
2224  {
2225  case FEATURE:
2226  header.properties[i].pmRowID = rowIdFeatures;
2227  featLabelGen.add(supLabel.internalName);
2228  rowIdFeatures++;
2229  if(prop.count != 1)
2230  {
2231  stringstream ss;
2232  ss << "PCD Parse Error: the field " << prop.field << " must have a count of 1";
2233  throw runtime_error(ss.str());
2234  }
2235  break;
2236  case DESCRIPTOR:
2237  header.properties[i].pmRowID = rowIdDescriptors;
2238  descLabelGen.add(supLabel.internalName, prop.count);
2239  rowIdDescriptors += prop.count;
2240  break;
2241  case TIME:
2242  header.properties[i].pmRowID = rowIdTime;
2243  timeLabelGen.add(supLabel.internalName, prop.count);
2244  rowIdTime += prop.count;
2245  default:
2246  throw runtime_error(string("PCD Implementation Error: encounter a type different from FEATURE, DESCRIPTOR and TIME. Implementation not supported. See the definition of 'enum PMPropTypes'"));
2247  break;
2248  }
2249 
2250  // we stop searching once we have a match
2251  break;
2252  }
2253  }
2254  }
2255 
2256  // loop through the remaining UNSUPPORTED labels and assigned them to a single descriptor row
2257  for(size_t i=0; i < header.properties.size(); i++)
2258  {
2259  const PCDproperty prop = header.properties[i];
2260  if(prop.pmType == UNSUPPORTED)
2261  {
2262  header.properties[i].pmType = DESCRIPTOR; // force descriptor
2263  header.properties[i].pmRowID = rowIdDescriptors;
2264  descLabelGen.add(prop.field, prop.count); // keep original name
2265  rowIdDescriptors += prop.count;
2266  }
2267  }
2268 
2269 
2271  // 3- RESERVE DATAPOINTS MEMORY
2272 
2273  const unsigned int featDim = featLabelGen.getLabels().totalDim();
2274  const unsigned int descDim = descLabelGen.getLabels().totalDim();
2275  const unsigned int timeDim = timeLabelGen.getLabels().totalDim();
2276  const unsigned int totalDim = featDim + descDim + timeDim;
2277  const unsigned int nbPoints = header.nbPoints;
2278 
2279  Matrix features = Matrix(featDim, nbPoints);
2280  Matrix descriptors = Matrix(descDim, nbPoints);
2281  Int64Matrix times = Int64Matrix(timeDim, nbPoints);
2282 
2283 
2285  // 4- PARSE PCD DATA
2286 
2287  size_t col = 0; // point count
2288  while (safeGetLine(is, line))
2289  {
2290 
2291  // get rid of white spaces before/after
2292  boost::trim (line);
2293 
2294  // ignore comments or empty line
2295  if (line.substr(0,1) == "#" || line == "")
2296  {
2297  lineNum++;
2298  continue;
2299  }
2300 
2301  vector<string> tokens;
2302  boost::split(tokens, line, boost::is_any_of("\t\r "), boost::token_compress_on);
2303 
2304 
2305  if (tokens.size() != totalDim)
2306  throw runtime_error(string("PCD Parse Error: number of data columns does not match number of fields at line: ") + boost::lexical_cast<string>(lineNum));
2307 
2308  unsigned int fileCol = 0;
2309  for(size_t i=0; i<header.properties.size(); i++)
2310  {
2311  const unsigned int count = header.properties[i].count;
2312  const unsigned int row = header.properties[i].pmRowID;
2313  const PMPropTypes type = header.properties[i].pmType;
2314 
2315 
2316  for(size_t j=0; j<count; j++)
2317  {
2318  switch (type)
2319  {
2320  case FEATURE:
2321  features(row+j, col) = boost::lexical_cast<T>(tokens[fileCol]);
2322  break;
2323  case DESCRIPTOR:
2324  descriptors(row+j, col) = boost::lexical_cast<T>(tokens[fileCol]);
2325  break;
2326  case TIME:
2327  times(row+j, col) = boost::lexical_cast<std::int64_t>(tokens[fileCol]);
2328  break;
2329  case UNSUPPORTED:
2330  throw runtime_error("Implementation error in loadPCD(). This should not throw.");
2331  break;
2332  }
2333 
2334  fileCol++;
2335  }
2336 
2337  }
2338 
2339  col++;
2340  lineNum++;
2341  }
2342 
2343  if (col != nbPoints)
2344  {
2345  stringstream ss;
2346  ss << "PCD Parse Error: the number of points in the file (" << col << ") is less than the specified number of points (" << nbPoints << ")";
2347  throw runtime_error(ss.str());
2348  }
2349 
2351  // 5- ASSEMBLE FINAL DATAPOINTS
2352 
2353  DataPoints loadedPoints(features, featLabelGen.getLabels());
2354 
2355  if (descriptors.rows() > 0)
2356  {
2357  loadedPoints.descriptors = descriptors;
2358  loadedPoints.descriptorLabels = descLabelGen.getLabels();
2359  }
2360 
2361  if(times.rows() > 0)
2362  {
2363  loadedPoints.times = times;
2364  loadedPoints.timeLabels = timeLabelGen.getLabels();
2365  }
2366 
2367  // Ensure homogeous coordinates
2368  if(!loadedPoints.featureExists("pad"))
2369  {
2370  loadedPoints.addFeature("pad", Matrix::Ones(1,features.cols()));
2371  }
2372 
2373  return loadedPoints;
2374 }
2375 
2376 template<typename T>
2378  const std::string& fileName, unsigned precision) {
2379  ofstream ofs(fileName.c_str());
2380  if (!ofs.good())
2381  throw runtime_error(string("Cannot open file ") + fileName);
2382  ofs.precision(precision);
2383  const int pointCount(data.features.cols());
2384  const int featCount(data.features.rows());
2385  const int descRows(data.descriptors.rows());
2386  const int descCount(data.descriptorLabels.size());
2387 
2388  if (pointCount == 0)
2389  {
2390  LOG_WARNING_STREAM("Warning, no points, doing nothing");
2391  return;
2392  }
2393 
2394  ofs << "# .PCD v.7 - Point Cloud Data file format\n" <<"VERSION .7\n";
2395  ofs << "FIELDS";
2396 
2397  for (int f=0; f < (featCount - 1); f++)
2398  {
2399  ofs << " " << data.featureLabels[f].text;
2400  }
2401 
2402  if (descRows == 0)
2403  ofs << "\n";
2404  else
2405  {
2406  for (int i = 0; i < descCount; i++)
2407  {
2408  ofs << " " << data.descriptorLabels[i].text;
2409  }
2410  ofs << "\n";
2411  }
2412 
2413  ofs << "SIZE";
2414  for (int i =0; i < featCount - 1 + descCount; i++)
2415  {
2416  ofs << " 4"; // for float
2417  }
2418  ofs << "\n";
2419 
2420  ofs << "TYPE";
2421  for (int i =0; i < featCount - 1 + descCount; i++)
2422  {
2423  ofs << " F"; // for float
2424  }
2425  ofs << "\n";
2426 
2427  ofs << "COUNT";
2428  for (int f = 0; f < featCount - 1 ; f++ )
2429  ofs << " 1";
2430  if (descCount == 0)
2431  ofs << "\n";
2432  else
2433  {
2434  for (int i = 0; i < descCount; i++)
2435  {
2436  ofs << " " << data.descriptorLabels[i].span;
2437  }
2438  ofs << "\n";
2439  }
2440 
2441  ofs << "WIDTH " << pointCount << "\n";
2442  ofs << "HEIGHT 1\n";
2443  ofs << "POINTS " << pointCount << "\n";
2444  ofs << "DATA ascii\n";
2445 
2446  // write points
2447  for (int p = 0; p < pointCount; ++p)
2448  {
2449  for (int f = 0; f < featCount - 1; ++f)
2450  {
2451  ofs << data.features(f, p);
2452  if(!(f == featCount-2 && descRows == 0))
2453  ofs << " ";
2454  }
2455  for (int d = 0; d < descRows; ++d)
2456  {
2457  ofs << data.descriptors(d, p);
2458  if(d != descRows-1)
2459  ofs << " ";
2460  }
2461  ofs << "\n";
2462  }
2463 
2464  ofs.close();
2465 }
2466 
2467 template
2468 void PointMatcherIO<float>::savePCD(const DataPoints& data, const std::string& fileName, unsigned precision);
2469 template
2470 void PointMatcherIO<double>::savePCD(const DataPoints& data, const std::string& fileName, unsigned precision);
PointMatcherIO::PCDheader::nbPoints
unsigned int nbPoints
number of points, same as width*height
Definition: IO.h:420
PointMatcherIO::GenericInputHeader
Helper structure designed to parse file headers.
Definition: IO.h:87
PointMatcherIO::PLYProperty::idx_type
std::string idx_type
for list properties, type of number of elements
Definition: IO.h:285
PointMatcherSupport::toParam
std::string toParam(const S &value)
Return the string value using lexical_cast.
Definition: Parametrizable.h:123
PointMatcherIO::PLYVertex
Implementation of PLY vertex element.
Definition: IO.h:359
PointMatcherIO::UNSUPPORTED
@ UNSUPPORTED
Definition: IO.h:69
PointMatcherIO::SplitTime::high32
Eigen::Matrix< unsigned int, Eigen::Dynamic, Eigen::Dynamic > high32
Matrix containing file data representing the high 32 bits.
Definition: IO.h:203
PointMatcher::DataPoints::descriptorLabels
Labels descriptorLabels
labels of descriptors
Definition: PointMatcher.h:334
PointMatcherIO::PLYProperty::is_list
bool is_list
member is true of property is a list
Definition: IO.h:287
PointMatcherIO::loadVTK
static DataPoints loadVTK(const std::string &fileName)
Load point cloud from a file as VTK.
Definition: pointmatcher/IO.cpp:904
PointMatcher::DataPoints::Label::text
std::string text
name of the label
Definition: PointMatcher.h:223
PointMatcherSupport::validateFile
void validateFile(const std::string &fileName)
Throw a runtime_error exception if fileName cannot be opened.
Definition: pointmatcher/IO.cpp:341
PointMatcherIO::PLYElement::name
std::string name
name identifying the PLY element
Definition: IO.h:330
PointMatcherIO::PLYProperty::PLYPropertyType::FLOAT64
@ FLOAT64
PointMatcherIO::PCDheader::height
unsigned int height
height of sensor matrix
Definition: IO.h:418
PointMatcherIO::LabelGenerator::getLabels
Labels getLabels() const
Return the vector of labels used to build a DataPoints.
Definition: pointmatcher/IO.cpp:442
PointMatcherIO::savePLY
static void savePLY(const DataPoints &data, const std::string &fileName, bool binary, unsigned precision)
save datapoints to PLY point cloud format
Definition: pointmatcher/IO.cpp:1722
PointMatcherIO::UNSTRUCTURED_GRID
@ UNSTRUCTURED_GRID
Definition: IO.h:194
PointMatcher::DataPoints::addTime
void addTime(const std::string &name, const Int64Matrix &newTime)
Add a time by name, remove first if already exists.
Definition: pointmatcher/DataPoints.cpp:637
build_map.T
T
Definition: build_map.py:34
PointMatcherIO::FEATURE
@ FEATURE
Definition: IO.h:66
PointMatcherIO::PCDheader::version
std::string version
Version of the PCD file used.
Definition: IO.h:415
PointMatcher::DataPoints::Labels
A vector of Label.
Definition: PointMatcher.h:229
icp_customized.name
string name
Definition: icp_customized.py:45
PointMatcherSupport::isBigEndian
const bool isBigEndian
true if platform is big endian
Definition: pointmatcher/IO.cpp:60
PointMatcherIO::PCDheader
All information contained in the header of a PCD file.
Definition: IO.h:413
PointMatcher::DataPoints::addFeature
void addFeature(const std::string &name, const Matrix &newFeature)
Add a feature by name, remove first if already exists. The 'pad' field will stay at the end for homog...
Definition: pointmatcher/DataPoints.cpp:436
PointMatcherIO::DESCRIPTOR
@ DESCRIPTOR
Definition: IO.h:67
PointMatcherIO::FileInfoVector::getTransform
TransformationParameters getTransform(const PointMatcherSupport::CsvElements &data, const std::string &prefix, unsigned dim, unsigned line)
Return the transformation named prefix from data.
Definition: pointmatcher/IO.cpp:320
PointMatcherIO::PCDproperty::pmType
PMPropTypes pmType
type of information in PointMatcher
Definition: IO.h:397
PointMatcherSupport::CsvElements
std::map< std::string, std::vector< std::string > > CsvElements
Data from a CSV file.
Definition: PointMatcher.h:125
PointMatcherIO::FileInfo::groundTruthTransformation
TransformationParameters groundTruthTransformation
matrix of the ground-truth transform
Definition: IO.h:238
PointMatcherIO::SupportedLabel::externalName
std::string externalName
name used in external format
Definition: IO.h:76
PointMatcherIO::FileInfo::readingFileName
std::string readingFileName
file name of the reading point cloud
Definition: IO.h:234
PointMatcherIO::PLYElement::num
unsigned num
number of occurences of the element
Definition: IO.h:331
PointMatcherIO::PCDheader::properties
std::vector< PCDproperty > properties
vector of properties
Definition: IO.h:416
PointMatcherSupport::readVtkData
std::istream & readVtkData(bool readBinary, MatrixRef into, std::istream &in)
Definition: IOFunctions.h:108
PointMatcher::DataPoints::addDescriptor
void addDescriptor(const std::string &name, const Matrix &newDescriptor)
Add a descriptor by name, remove first if already exists.
Definition: pointmatcher/DataPoints.cpp:533
PointMatcherIO::SplitTime
Storage for time loaded separatly.
Definition: IO.h:198
PointMatcherIO::PLYProperty
Interface for PLY property.
Definition: IO.h:267
PointMatcherIO::PLYElementF::createElement
static PLYElement * createElement(const std::string &elem_name, const int elem_num, const unsigned offset)
factory function, build element defined by name with elem_num elements
Definition: pointmatcher/IO.cpp:1915
icp_customized.trim
trim
Definition: icp_customized.py:76
PointMatcher
Functions and classes that are dependant on scalar type are defined in this templatized class.
Definition: PointMatcher.h:130
PointMatcherIO::PLYProperty::operator==
bool operator==(const PLYProperty &other) const
list prop ctor
Definition: pointmatcher/IO.cpp:1958
PointMatcherPrivate.h
PointMatcherIO::SupportedLabel::SupportedLabel
SupportedLabel(const std::string &internalName, const std::string &externalName, const PMPropTypes &type)
Constructor.
Definition: pointmatcher/IO.cpp:403
PointMatcherIO::FileInfo::referenceFileName
std::string referenceFileName
file name of the reference point cloud
Definition: IO.h:235
PointMatcherIO::PCDheader::width
unsigned int width
width of sensor matrix
Definition: IO.h:417
PointMatcherIO::PLYElement
Interface for all PLY elements.
Definition: IO.h:327
PointMatcher::DataPoints
A point cloud.
Definition: PointMatcher.h:207
PointMatcherIO::FileInfoVector::FileInfoVector
FileInfoVector()
Definition: pointmatcher/IO.cpp:178
PointMatcherIO::SupportedVTKDataTypes
SupportedVTKDataTypes
Enumeration of legacy VTK data types that can be parsed.
Definition: IO.h:191
PointMatcherIO::TIME
@ TIME
Definition: IO.h:68
testing::internal::string
::std::string string
Definition: gtest.h:1979
PointMatcher::DataPoints::timeLabels
Labels timeLabels
labels of times.
Definition: PointMatcher.h:336
PointMatcherIO::PLYElementF::elementSupported
bool elementSupported(const std::string &elem_name)
returns true if element named elem_name is supported by this parser
Definition: pointmatcher/IO.cpp:1908
PointMatcherIO::PLYProperty::pmRowID
int pmRowID
row id used in a DataPoints
Definition: IO.h:291
IOFunctions.h
PointMatcherIO::PLYProperty::PLYPropertyType::FLOAT32
@ FLOAT32
PointMatcherIO::FileInfoVector::findTransform
bool findTransform(const PointMatcherSupport::CsvElements &data, const std::string &prefix, unsigned dim)
Return whether there is a valid transformation named prefix in data.
Definition: pointmatcher/IO.cpp:303
PointMatcherIO::SupportedLabel::type
PMPropTypes type
type of information in PointMatcher
Definition: IO.h:77
PointMatcherIO::PLYProperty::PLYPropertyType::UINT16
@ UINT16
PointMatcherIO::PLYProperty::PLYPropertyType::INT16
@ INT16
PointMatcherIO::PCDproperty::field
std::string field
Name of the property.
Definition: IO.h:391
PointMatcherIO::PLYProperty::PLYProperty
PLYProperty(const std::string &type, const std::string &name, const unsigned pos)
@(brief) Regular PLY property constructor
Definition: pointmatcher/IO.cpp:1831
PointMatcher::DataPoints::featureExists
bool featureExists(const std::string &name) const
Look if a feature with a given name exist.
Definition: pointmatcher/DataPoints.cpp:487
PointMatcherIO::loadCSV
static DataPoints loadCSV(const std::string &fileName)
Associate an external name to a DataPoints type of information.
Definition: pointmatcher/IO.cpp:393
PointMatcherIO::Vector
PointMatcher< T >::Vector Vector
alias
Definition: IO.h:45
PointMatcherIO::loadPLY
static DataPoints loadPLY(const std::string &fileName)
Load polygon file format (ply) file.
Definition: pointmatcher/IO.cpp:1282
PointMatcherIO::PLYProperty::name
std::string name
name of PLY property
Definition: IO.h:283
PointMatcherIO::SupportedLabels
std::vector< SupportedLabel > SupportedLabels
Vector of supported labels in PointMatcher and their external names.
Definition: IO.h:84
skipBlock
void skipBlock(bool binary, int binarySize, std::istream &is, bool hasSeparateSizeParameter=true)
Definition: pointmatcher/IO.cpp:912
PointMatcherIO::it_PLYProp
PLYProperties::iterator it_PLYProp
Iterator for a vector of PLY properties.
Definition: IO.h:324
PointMatcherSupport::safeGetLine
std::istream & safeGetLine(std::istream &is, std::string &t)
Replaces getline for handling windows style CR/LF line endings.
Definition: IOFunctions.cpp:7
PointMatcherIO::SupportedLabel::internalName
std::string internalName
name used in PointMatcher
Definition: IO.h:75
PointMatcherSupport::oneBigEndian
const int oneBigEndian
is always a big endian independent of the platforms endianness
Definition: pointmatcher/IO.cpp:61
PointMatcherIO::FileInfo::configFileName
std::string configFileName
file name of the yaml configuration
Definition: IO.h:236
PointMatcherIO::PLYProperty::type
PLYPropertyType type
type of PLY property
Definition: IO.h:284
PointMatcherIO::PMPropTypes
PMPropTypes
Type of information in a DataPoints. Each type is stored in its own dense matrix.
Definition: IO.h:64
PointMatcherIO::PLYProperty::PLYPropertyType::INT8
@ INT8
PointMatcher::DataPoints::descriptors
Matrix descriptors
descriptors of points in the cloud, might be empty
Definition: PointMatcher.h:333
csvLineToVector
static std::vector< string > csvLineToVector(const char *line)
Definition: pointmatcher/IO.cpp:69
icp.data
data
Definition: icp.py:50
PointMatcherIO::PLYElement::operator==
bool operator==(const PLYElement &other) const
comparison operator for elements
Definition: pointmatcher/IO.cpp:1951
PointMatcherIO::FileInfoVector
A vector of file info, to be used in batch processing.
Definition: IO.h:245
PointMatcherIO::FileInfoVector::localToGlobalFileName
std::string localToGlobalFileName(const std::string &path, const std::string &fileName)
Join parentPath and fileName and return the result as a global path.
Definition: pointmatcher/IO.cpp:289
PointMatcherIO::PLYProperty::PLYPropertyType::UINT32
@ UINT32
PointMatcherIO::PLYElement::properties
PLYProperties properties
all properties found in the header
Definition: IO.h:334
PointMatcherIO::PLYProperty::PLYPropertyType::INT32
@ INT32
PointMatcherIO::PLYProperty::PLYPropertyType::UINT8
@ UINT8
LOG_WARNING_STREAM
#define LOG_WARNING_STREAM(args)
Definition: PointMatcherPrivate.h:68
PointMatcherIO::Matrix
PointMatcher< T >::Matrix Matrix
alias
Definition: IO.h:46
PointMatcherIO::SupportedLabel
Structure containing all information required to map external information to PointMatcher internal re...
Definition: IO.h:73
PointMatcherIO::LabelGenerator::add
void add(const std::string internalName)
add a name to the vector of labels. If already there, will increament the dimension.
Definition: pointmatcher/IO.cpp:413
PointMatcherIO::saveCSV
static void saveCSV(const DataPoints &data, const std::string &fileName, unsigned precision)
Save point cloud to a file as CSV.
Definition: pointmatcher/IO.cpp:829
dataPath
std::string dataPath
Definition: utest.cpp:43
PointMatcherIO::getColLabel
static std::string getColLabel(const Label &label, const int row)
convert a descriptor label to an appropriate sub-label
Definition: pointmatcher/IO.cpp:454
PointMatcherIO::POLYDATA
@ POLYDATA
Definition: IO.h:193
PointMatcherIO::TransformationParameters
PointMatcher< T >::TransformationParameters TransformationParameters
alias
Definition: IO.h:49
PointMatcherIO::PCDheader::viewPoint
Eigen::Matrix< T, 7, 1 > viewPoint
not used
Definition: IO.h:419
PointMatcherIO::Int64Matrix
PointMatcher< T >::Int64Matrix Int64Matrix
alias
Definition: IO.h:47
PointMatcherIO::getSupportedExternalLabels
static const SupportedLabels & getSupportedExternalLabels()
Definition: IO.h:117
parseCsvWithHeader
CsvElements parseCsvWithHeader(const std::string &fileName)
Definition: pointmatcher/IO.cpp:91
PointMatcherIO::Label
PointMatcher< T >::DataPoints::Label Label
alias
Definition: IO.h:51
PointMatcherIO::PLYElement::total_props
unsigned total_props
total number of properties in PLY element
Definition: IO.h:332
PointMatcher::DataPoints::times
Int64Matrix times
time associated to each points, might be empty
Definition: PointMatcher.h:335
std
PointMatcherIO::FileInfo::initialTransformation
TransformationParameters initialTransformation
matrix of initial estimate transform
Definition: IO.h:237
PointMatcher::DataPoints::save
void save(const std::string &fileName, bool binary=false, unsigned precision=7) const
Save a point cloud to a file, determine format from extension.
Definition: pointmatcher/IO.cpp:794
PointMatcherIO::FileInfo
Information to exploit a reading from a file using this library. Fields might be left blank if unused...
Definition: IO.h:230
icp_advance_api.dim
dim
Definition: icp_advance_api.py:152
PointMatcher::DataPoints::Label::span
size_t span
number of data dimensions the label spans
Definition: PointMatcher.h:224
PointMatcherIO::savePCD
static void savePCD(const DataPoints &data, const std::string &fileName, unsigned precision)
save datapoints to PCD point cloud format
Definition: pointmatcher/IO.cpp:2377
PointMatcherIO::SplitTime::low32
Eigen::Matrix< unsigned int, Eigen::Dynamic, Eigen::Dynamic > low32
Matrix containing file data representing the low 32 bits.
Definition: IO.h:205
build_map.transformation
transformation
Definition: build_map.py:37
InspectorsImpl.h
InspectorsImpl::VTKFileInspector
Definition: InspectorsImpl.h:159
PointMatcherIO::saveVTK
static void saveVTK(const DataPoints &data, const std::string &fileName, bool binary=false, unsigned precision=7)
Save point cloud to a file as VTK.
Definition: pointmatcher/IO.cpp:1255
PointMatcher::DataPoints::Labels::totalDim
size_t totalDim() const
Return the sum of the spans of each label.
Definition: pointmatcher/DataPoints.cpp:87
PointMatcherIO::PLYElementF
Factory for PLY elements.
Definition: IO.h:374
PointMatcherIO::PLYElementF::getElementType
static ElementTypes getElementType(const std::string &elem_name)
Definition: pointmatcher/IO.cpp:1892
PointMatcherSupport
Functions and classes that are not dependant on scalar type are defined in this namespace.
Definition: Bibliography.cpp:45
build_map.end
end
Definition: build_map.py:79
PointMatcherIO::PCDproperty
Information for a PCD property.
Definition: IO.h:389
PointMatcherIO::PLYElementF::ElementTypes
ElementTypes
Definition: IO.h:376
PointMatcher::DataPoints::load
static DataPoints load(const std::string &fileName)
Load a point cloud from a file, determine format from extension.
Definition: pointmatcher/IO.cpp:353
PointMatcherIO::PLYProperty::get_type_from_string
PLYPropertyType get_type_from_string(const std::string &s)
compare with other property
Definition: IO.h:302
IO.h
PointMatcherIO::PCDproperty::count
unsigned int count
number of dimension
Definition: IO.h:394
PointMatcherIO::FileInfo::FileInfo
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())
Constructor, leave fields blank if unused.
Definition: pointmatcher/IO.cpp:164
PointMatcherIO::PCDheader::dataType
std::string dataType
ascii or binary
Definition: IO.h:421
PointMatcherIO::plyPropTypeValid
static bool plyPropTypeValid(const std::string &type)
Check that property defined by type is a valid PLY type note: type must be lowercase.
Definition: pointmatcher/IO.cpp:1926
PointMatcherIO::loadPCD
static DataPoints loadPCD(const std::string &fileName)
PointMatcherSupport::Parametrizable::Parameters
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
Definition: Parametrizable.h:199
PointMatcherIO::PLYProperty::pmType
PMPropTypes pmType
type of information in PointMatcher
Definition: IO.h:290
PointMatcher::DataPoints::Label
The name for a certain number of dim.
Definition: PointMatcher.h:221
PointMatcherIO::LabelGenerator
Generate a vector of Labels by checking for collision is the same name is reused.
Definition: IO.h:162


libpointmatcher
Author(s):
autogenerated on Sun Dec 22 2024 03:21:53