47 #include "boost/algorithm/string.hpp"
49 #include "boost/lexical_cast.hpp"
50 #include "boost/foreach.hpp"
53 #define strtok_r strtok_s
60 const bool isBigEndian = *
reinterpret_cast<const unsigned char*
>(&one) ==
static_cast<unsigned char>(0);
71 std::vector<string> parsedLine;
72 char delimiters[] =
" \t,;";
76 strcpy(tmpLine, line);
77 token = strtok_r(tmpLine, delimiters, &brkt);
82 parsedLine.push_back(
string(token));
83 token = strtok_r(NULL, delimiters, &brkt);
95 ifstream is(fileName.c_str());
97 unsigned elementCount=0;
98 std::map<string, unsigned> keywordCols;
101 bool firstLine(
true);
102 unsigned lineCount=0;
112 elementCount = header.size();
113 for(
unsigned int i = 0; i < elementCount; i++)
115 keywordCols[header[i]] = i;
123 if(parsedLine.size() != elementCount && parsedLine.size() !=0)
125 stringstream errorMsg;
126 errorMsg <<
"Error at line " << lineCount+1 <<
": expecting " << elementCount <<
" columns but read " << parsedLine.size() <<
" elements.";
127 throw runtime_error(errorMsg.str());
130 for(
unsigned int i = 0; i < parsedLine.size(); i++)
132 for(BOOST_AUTO(it,keywordCols.begin()); it!=keywordCols.end(); it++)
134 if(i == (*it).second)
136 data[(*it).first].push_back(parsedLine[i]);
165 readingFileName(readingFileName),
166 referenceFileName(referenceFileName),
167 configFileName(configFileName),
168 initialTransformation(initialTransformation),
169 groundTruthTransformation(groundTruthTransformation),
201 dataPath = std::filesystem::path(fileName).parent_path().string();
203 if (configPath.empty())
205 configPath = std::filesystem::path(fileName).parent_path().string();
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;
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"));
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())
238 referenceFileNames = referenceIt->second;
239 assert (referenceFileNames->size() == lineCount);
241 if (configIt !=
data.end())
243 configFileNames = configIt->second;
244 assert (configFileNames->size() == lineCount);
248 for(
unsigned line=0; line<lineCount; line++)
254 if (referenceFileNames)
257 info.
configFileName = localToGlobalFileName(configPath, (*configFileNames)[line]);
260 if(found3dInitialTrans)
262 if(found2dInitialTrans)
264 if(found3dGroundTruthTrans)
266 if(found2dGroundTruthTrans)
270 this->push_back(info);
292 if (!std::filesystem::exists(globalFileName))
294 const std::filesystem::path globalFilePath(std::filesystem::path(parentPath) / std::filesystem::path(fileName));
295 globalFileName = globalFilePath.string();
298 return globalFileName;
306 for(
unsigned i=0; i<
dim+1; i++)
308 for(
unsigned j=0; j<
dim+1; j++)
310 stringstream transName;
311 transName << prefix << i << j;
312 found = found && (
data.find(transName.str()) !=
data.end());
323 for(
unsigned i=0; i<
dim+1; i++)
325 for(
unsigned j=0; j<
dim+1; j++)
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]);
343 std::filesystem::path fullPath(fileName);
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());
355 const std::filesystem::path path(fileName);
356 if (path.has_extension())
358 const string& ext(path.extension().string());
361 else if(ext ==
".csv")
363 else if(ext ==
".ply")
365 else if(ext ==
".pcd")
368 throw runtime_error(
"loadAnyFormat(): Unknown extension \"" + ext +
"\" for file \"" + fileName +
"\", extension must be either \".vtk\", \".ply\", \".pcd\" or \".csv\"");
372 throw runtime_error(
"loadAnyFormat(): Missing extension for file \"" + fileName +
"\", extension must be either \".vtk\", \".ply\", \".pcd\" or \".csv\"");
395 ifstream ifs(fileName.c_str());
404 internalName(internalName),
405 externalName(externalName),
415 bool findLabel =
false;
416 for(
size_t i=0; i<labels.size(); ++i)
418 if(internalName == labels[i].text)
429 labels.push_back(
Label(internalName,1));
436 labels.push_back(
Label(internalName,
dim));
451 template <
typename T>
457 if (label.
text ==
"normals")
472 else if (label.
text ==
"color")
476 externalName =
"red";
480 externalName =
"green";
484 externalName =
"blue";
487 externalName =
"alpha";
489 else if (label.
text ==
"eigValues")
491 externalName =
"eigValues" + boost::lexical_cast<string>(row);
493 else if (label.
text ==
"eigVectors")
496 externalName =
"eigVectors" + boost::lexical_cast<string>(row/3);
498 int row_mod = row % 3;
501 else if (row_mod == 1)
503 else if (row_mod == 2)
506 else if (label.
span == 1)
508 externalName = label.
text;
511 externalName = label.
text + boost::lexical_cast<std::string>(row);
522 vector<GenericInputHeader> csvHeader;
527 unsigned int csvCol = 0;
528 unsigned int csvRow = 0;
529 bool hasHeader(
false);
530 bool firstLine(
true);
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>(),
541 is.seekg(0, ios::beg);
543 char delimiters[] =
" \t,;";
554 unsigned int len = strspn(line.c_str(),
" ,+-.1234567890Ee");
555 if(len != line.length())
568 unsigned int dim = 0;
570 strcpy(tmpLine, line.c_str());
572 token = strtok_r(tmpLine, delimiters, &brkt);
583 token = strtok_r(NULL, delimiters, &brkt);
589 if (!(
dim == 2 ||
dim == 3))
591 int idX=0, idY=0, idZ=0;
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: ";
596 cout <<
"Enter column ID (starting from 0) for y: ";
598 cout <<
"Enter column ID (starting from 0, -1 if 2D data) for z: ";
602 for(
unsigned int i=0; i<
dim; i++)
604 std::ostringstream os;
631 int rowIdFeatures = 0;
632 int rowIdDescriptors = 0;
637 for(
size_t i=0; i<externalLabels.size(); i++)
641 for(
size_t j=0; j < csvHeader.size(); j++)
645 csvHeader[j].matrixType = supLabel.
type;
647 switch (supLabel.
type)
650 csvHeader[j].matrixRowId = rowIdFeatures;
655 csvHeader[j].matrixRowId = rowIdDescriptors;
660 csvHeader[j].matrixRowId = rowIdTime;
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'"));
676 for(
unsigned int i=0; i<csvHeader.size(); i++)
681 csvHeader[i].matrixRowId = rowIdDescriptors;
682 descLabelGen.
add(csvHeader[i].
name);
689 if(hasHeader && line_count > 0)
695 const unsigned int nbPoints = line_count;
697 features =
Matrix(featDim, nbPoints);
698 descriptors =
Matrix(descDim, nbPoints);
706 strcpy(line_c,line.c_str());
707 token = strtok_r(line_c, delimiters, &brkt);
709 if(!(hasHeader && firstLine))
715 if(csvCol > (csvHeader.size() - 1))
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());
723 const int matrixRow = csvHeader[csvCol].matrixRowId;
724 const int matrixCol = csvRow;
726 switch (csvHeader[csvCol].matrixType)
729 features(matrixRow, matrixCol) = lexical_cast_scalar_to_string<T>(
string(token));
732 descriptors(matrixRow, matrixCol) = lexical_cast_scalar_to_string<T>(token);
735 times(matrixRow, matrixCol) = lexical_cast_scalar_to_string<std::int64_t>(token);
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'"));
744 token = strtok_r(NULL, delimiters, &brkt);
750 if(csvCol != (csvHeader.size()))
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());
766 if (descriptors.rows() > 0)
774 loadedPoints.
times = times;
781 loadedPoints.
addFeature(
"pad", Matrix::Ones(1,features.cols()));
796 const std::filesystem::path path(fileName);
797 if (path.has_extension())
799 const string& ext(path.extension().string());
800 if (boost::iequals(ext,
".vtk"))
802 else if (boost::iequals(ext,
".ply"))
806 throw runtime_error(
"save(): Binary writing is not supported together with extension \"" + ext +
"\". Currently binary writing is only supported with \".vtk\" and \".ply\".");
808 if (boost::iequals(ext,
".csv"))
810 else if (boost::iequals(ext,
".pcd"))
813 throw runtime_error(
"save(): Unknown extension \"" + ext +
"\" for file \"" + fileName +
"\", extension must be either \".vtk\", \".ply\", \".pcd\" or \".csv\"");
818 throw runtime_error(
"save(): Missing extension for file \"" + fileName +
"\", extension must be either \".vtk\", \".ply\", \".pcd\" or \".csv\"");
831 ofstream ofs(fileName.c_str());
833 throw runtime_error(
string(
"Cannot open file ") + fileName);
834 ofs.precision(precision);
842 const int pointCount(
data.features.cols());
843 const int dimCount(
data.features.rows());
844 const int descDimCount(
data.descriptors.rows());
853 for (
int i = 0; i < dimCount - 1; i++)
855 os <<
data.featureLabels[i].text;
857 if (!((i == (dimCount - 2)) && descDimCount == 0))
862 for (
size_t i = 0; i <
data.descriptorLabels.size(); i++)
865 for (
size_t s = 0; s < lab.
span; s++)
868 if (n != (descDimCount - 1))
877 for (
int p = 0; p < pointCount; ++p)
879 for (
int i = 0; i < dimCount-1; ++i)
881 os <<
data.features(i, p);
882 if(!((i == (dimCount - 2)) && descDimCount == 0))
886 for (
int i = 0; i < descDimCount; i++)
888 os <<
data.descriptors(i,p);
889 if (i != (descDimCount - 1))
906 ifstream ifs(fileName.c_str(), std::ios::binary);
908 throw runtime_error(
string(
"Cannot open file ") + fileName);
912 void skipBlock(
bool binary,
int binarySize, std::istream & is,
bool hasSeparateSizeParameter =
true){
917 throw std::runtime_error(
"File violates the VTK format : parameter 'n' is missing after a field name.");
920 if(hasSeparateSizeParameter) {
923 throw std::runtime_error(
"File violates the VTK format : parameter 'size' is missing after a field name.");
932 is.seekg(size * binarySize, std::ios_base::cur);
934 for (
int p = 0; p < n; p++)
945 std::map<std::string, SplitTime> labelledSplitTime;
952 if (line.find(
"# vtk DataFile Version") != 0)
953 throw runtime_error(
string(
"Wrong magic header, found ") + line);
957 const bool isBinary = (line ==
"BINARY");
958 if (line !=
"ASCII"){
960 throw runtime_error(
string(
"Wrong file type, expecting ASCII or BINARY, found ") + line);
966 if (line ==
"DATASET POLYDATA")
968 else if (line ==
"DATASET UNSTRUCTURED_GRID")
971 throw runtime_error(
string(
"Wrong data type, expecting DATASET POLYDATA, found ") + line);
981 while (is >> fieldName)
984 if(fieldName ==
"POINTS")
990 if(!(type ==
"float" || type ==
"double"))
991 throw runtime_error(
string(
"Field POINTS can only be of type double or float"));
993 Matrix features(4, pointCount);
994 for (
int p = 0; p < pointCount; ++p)
996 readVtkData(type, isBinary, features.template block<3, 1>(0, p), is);
997 features(3, p) = 1.0;
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));
1008 else if(dataType ==
POLYDATA && fieldName ==
"VERTICES")
1013 else if(dataType ==
POLYDATA && fieldName ==
"LINES")
1018 else if(dataType ==
POLYDATA && fieldName ==
"POLYGONS")
1023 else if(dataType ==
POLYDATA && fieldName ==
"TRIANGLE_STRIPS")
1040 else if(fieldName ==
"POINT_DATA")
1042 int descriptorCount;
1043 is >> descriptorCount;
1044 if(pointCount != descriptorCount)
1045 throw runtime_error(
string(
"The size of POINTS is different than POINT_DATA"));
1049 else if (fieldName ==
"FIELD")
1051 string fieldDataName;
1053 is >> fieldDataName >> fieldDataCount;
1055 for (
int f = 0; f < fieldDataCount; f++)
1058 is >>
name >>
dim >> numTuples >> type;
1060 if(type ==
"vtkIdType")
1063 is.seekg(
dim * numTuples * 4, std::ios_base::cur);
1066 for (
int t = 0; t <
dim * numTuples; t++ )
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"));
1077 readVtkData(type, isBinary, descriptor.transpose(), is);
1081 else if(fieldName ==
"METADATA")
1085 while(!line.empty())
1096 bool isTimeSec =
false;
1097 bool isTimeNsec =
false;
1100 if(boost::algorithm::ends_with(
name,
"_splitTime_high32"))
1103 boost::algorithm::erase_last(
name,
"_splitTime_high32");
1106 if(boost::algorithm::ends_with(
name,
"_splitTime_low32"))
1109 boost::algorithm::erase_last(
name,
"_splitTime_low32");
1113 bool skipLookupTable =
false;
1114 bool isColorScalars =
false;
1115 if(fieldName ==
"SCALARS")
1119 skipLookupTable =
true;
1121 else if(fieldName ==
"VECTORS")
1126 else if(fieldName ==
"TENSORS")
1131 else if(fieldName ==
"NORMALS")
1136 else if(fieldName ==
"COLOR_SCALARS")
1140 isColorScalars =
true;
1143 throw runtime_error(
string(
"Unknown field name " + fieldName +
", expecting SCALARS, VECTORS, TENSORS, NORMALS or COLOR_SCALARS."));
1150 if(isTimeSec || isTimeNsec)
1158 typename std::map<std::string, SplitTime>::iterator it;
1160 it = labelledSplitTime.find(
name);
1162 if(it == labelledSplitTime.end())
1165 t.
high32 = Eigen::Matrix<unsigned int, Eigen::Dynamic, Eigen::Dynamic> (
dim, pointCount);
1167 labelledSplitTime[
name] = t;
1173 assert(labelledSplitTime[
name].isHigh32Found ==
false);
1174 readVtkData(type, isBinary, labelledSplitTime[
name].high32.transpose(), is);
1175 labelledSplitTime[
name].isHigh32Found =
true;
1181 assert(labelledSplitTime[
name].isLow32Found ==
false);
1182 readVtkData(type, isBinary, labelledSplitTime[
name].low32.transpose(), is);
1183 labelledSplitTime[
name].isLow32Found =
true;
1191 if(isColorScalars && isBinary)
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);
1203 if(!(type ==
"float" || type ==
"double"))
1204 throw runtime_error(
string(
"Field " + fieldName +
" is " + type +
" but can only be of type double or float."));
1211 readVtkData(type, isBinary, descriptorData.transpose(), is);
1219 typename std::map<std::string, SplitTime>::iterator it;
1220 for(it=labelledSplitTime.begin(); it!=labelledSplitTime.end(); it++)
1223 if(it->second.isHigh32Found ==
false)
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."));
1228 if(it->second.isLow32Found ==
false)
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."));
1235 for(
int i=0; i<it->second.high32.cols(); i++)
1238 timeData(0,i) = (((std::int64_t) it->second.high32(0,i)) << 32) | ((std::int64_t) it->second.low32(0,i));
1241 loadedPoints.
addTime(it->first, timeData);
1244 return loadedPoints;
1254 template<
typename T>
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);
1281 template<
typename T>
1284 ifstream ifs(fileName.c_str());
1286 throw runtime_error(
string(
"Cannot open file ") + fileName);
1297 template <
typename T>
1300 class Elements :
public vector<PLYElement*>{
1303 for (
typename vector<PLYElement*>::const_iterator it = this->begin(); it != this->
end(); it++ )
1332 bool format_defined =
false;
1333 bool header_processed =
false;
1338 bool skip_props =
false;
1339 unsigned elem_offset = 0;
1340 bool is_binary =
false;
1344 if (line.find(
"ply") != 0) {
1345 throw runtime_error(
string(
"PLY parse error: wrong magic header, found <") + line +
string(
">"));
1348 while (!header_processed)
1351 throw runtime_error(
"PLY parse error: reached end of file before end of header definition");
1356 istringstream stringstream (line);
1359 stringstream >> keyword;
1362 if (keyword ==
"comment") {
1367 if (keyword ==
"format")
1370 throw runtime_error(
"PLY parse error: format already defined");
1372 string format_str, version_str;
1373 stringstream >> format_str >> version_str;
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"));
1378 if (format_str ==
"binary_little_endian")
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")
1384 throw runtime_error(
string(
"PLY parse error: version <") + version_str +
string(
"> of ply is not supported"));
1387 format_defined =
true;
1390 else if (keyword ==
"element")
1394 string elem_name, elem_num_s;
1395 stringstream >> elem_name >> elem_num_s;
1400 elem_num = boost::lexical_cast<unsigned>(elem_num_s);
1402 catch (boost::bad_lexical_cast&)
1404 throw runtime_error(
string(
"PLY parse error: bad number of elements ") + elem_num_s +
string(
" for element ") + elem_name);
1411 current_element = elem;
1414 for (
typename Elements::const_iterator it = elements.begin(); it != elements.end(); it++ )
1416 if (**it == *elem) {
1418 throw runtime_error(
string(
"PLY parse error: element: ") + elem_name +
string(
"is already defined"));
1421 elements.push_back(elem);
1426 LOG_WARNING_STREAM(
"PLY parse warning: element " << elem_name <<
" not supported. Skipping.");
1430 elem_offset += elem_num;
1432 else if (keyword ==
"property")
1434 if (current_element == NULL)
1436 throw runtime_error(
"PLY parse error: property listed without defining an element");
1442 string next, prop_type, prop_name;
1443 stringstream >> next;
1448 string prop_idx_type;
1449 stringstream >> prop_idx_type >> prop_type >> prop_name;
1453 current_element->
properties.push_back(list_prop);
1459 stringstream >> prop_name;
1467 else if (keyword ==
"end_header")
1469 if (!format_defined)
1471 throw runtime_error(
string(
"PLY parse error: format not defined in header"));
1474 if (elements.size() == 0)
1476 throw runtime_error(
string(
"PLY parse error: no elements defined in header"));
1479 header_processed =
true;
1489 if(vertex->
name !=
"vertex")
1491 throw runtime_error(
string(
"PLY parse error: vertex should be the first element defined."));
1497 int rowIdFeatures = 0;
1498 int rowIdDescriptors = 0;
1505 for(
size_t i=0; i<externalLabels.size(); i++)
1515 it->pmType = supLabel.
type;
1518 switch (supLabel.
type)
1521 it->pmRowID = rowIdFeatures;
1526 it->pmRowID = rowIdDescriptors;
1531 it->pmRowID = rowIdTime;
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'"));
1551 it->pmRowID = rowIdDescriptors;
1552 descLabelGen.
add(it->name);
1563 const unsigned int nbPoints = vertex->
num;
1573 const int nbValues = nbPoints*nbProp;
1576 for(
int i=0; i<nbValues; i++)
1586 is.read(
reinterpret_cast<char*
>(&temp),
sizeof(int8_t));
1587 value =
static_cast<T>(temp);
1593 is.read(
reinterpret_cast<char*
>(&temp),
sizeof(uint8_t));
1594 value =
static_cast<T>(temp);
1600 is.read(
reinterpret_cast<char*
>(&temp),
sizeof(int16_t));
1601 value =
static_cast<T>(temp);
1607 is.read(
reinterpret_cast<char*
>(&temp),
sizeof(uint16_t));
1608 value =
static_cast<T>(temp);
1615 is.read(
reinterpret_cast<char*
>(&temp),
sizeof(int32_t));
1616 value =
static_cast<T>(temp);
1623 is.read(
reinterpret_cast<char*
>(&temp),
sizeof(uint32_t));
1624 value =
static_cast<T>(temp);
1630 is.read(
reinterpret_cast<char*
>(&temp),
sizeof(float));
1631 value =
static_cast<T>(temp);
1638 is.read(
reinterpret_cast<char*
>(&temp),
sizeof(double));
1639 value =
static_cast<T>(temp);
1644 throw runtime_error(
1645 (boost::format(
"Unsupported data type in binary mode %1%.") %
static_cast<int>(vertex->
properties[propID].type)).str());
1649 if ((is_binary && !is) || (!is_binary && !(is >> value)))
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 %
1657 const int row = vertex->
properties[propID].pmRowID;
1671 features(row, col) = value;
1674 descriptors(row, col) = value;
1677 times(row, col) = value;
1680 throw runtime_error(
"Implementation error in loadPLY(). This should not throw.");
1686 if(propID >= nbProp)
1699 if (descriptors.rows() > 0)
1705 if(times.rows() > 0)
1707 loadedPoints.
times = times;
1714 loadedPoints.
addFeature(
"pad", Matrix::Ones(1,features.cols()));
1717 return loadedPoints;
1721 template<
typename T>
1723 const std::string& fileName,
bool binary,
unsigned precision)
1727 ofstream ofs(fileName.c_str());
1729 throw runtime_error(
string(
"Cannot open file ") + fileName);
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());
1737 if (pointCount == 0)
1744 ofs <<
"ply\n" <<
"format binary_little_endian 1.0\n";
1746 ofs <<
"ply\n" <<
"format ascii 1.0\n";
1748 ofs <<
"comment File created with libpointmatcher\n";
1749 ofs <<
"element vertex " << pointCount <<
"\n";
1752 using ValueType =
typename std::conditional<std::is_same<T, float>::value, float,
double>::type;
1753 if (std::is_same<ValueType, float>::value)
1756 dataType =
"double";
1758 for (
int f=0; f <(featCount-1); f++)
1760 ofs <<
"property " << dataType <<
" " <<
data.featureLabels[f].text <<
"\n";
1763 for (
size_t i = 0; i <
data.descriptorLabels.size(); i++)
1766 for (
size_t s = 0; s < lab.
span; s++)
1769 if (label ==
"red" || label ==
"green" || label ==
"blue" || label ==
"alpha")
1770 ofs <<
"property uchar " << label <<
"\n";
1772 ofs <<
"property " << dataType <<
" " << label <<
"\n";
1776 ofs <<
"end_header\n";
1779 for (
int p = 0; p < pointCount; ++p)
1781 for (
int f = 0; f < featCount - 1; ++f)
1785 ofs.write(
reinterpret_cast<const char*
>(&
data.features(f, p)),
sizeof(
T));
1789 ofs <<
data.features(f, p);
1790 if(!(f == featCount - 2 && descRows == 0))
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)
1800 if (datawithColor && d >= colorStartingRow && d < colorEndRow) {
1803 char value =
static_cast<char>(
data.descriptors(d, p) * 255.0);
1804 ofs.write(
reinterpret_cast<const char*
>(&value),
sizeof(char));
1807 ofs << static_cast<unsigned>(
data.descriptors(d, p) * 255.0);
1810 ofs.write(
reinterpret_cast<const char*
>(&
data.descriptors(d, p)),
sizeof(
T));
1812 ofs <<
data.descriptors(d, p);
1814 if(d != descRows-1 && !binary)
1830 template<
typename T>
1843 throw std::runtime_error(
1855 template<
typename T>
1869 throw std::runtime_error(
1891 template <
typename T>
1894 string lc = elem_name;
1895 boost::algorithm::to_lower(lc);
1907 template <
typename T>
1914 template<
typename T>
1916 const std::string& elem_name,
const int elem_num,
const unsigned offset) {
1925 template<
typename T>
1927 return (type ==
"char" || type ==
"uchar" || type ==
"short"
1928 || type ==
"ushort" || type ==
"int" || type ==
"uint"
1929 || type ==
"float" || type ==
"double");
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);
1950 template <
typename T>
1957 template <
typename T>
1966 template<
typename T>
1968 ifstream ifs(fileName.c_str());
1970 throw runtime_error(
string(
"Cannot open file ") + fileName);
1983 template<
typename T>
2029 if (line.substr(0,1) ==
"#" || line ==
"")
2035 vector<string> tokens;
2036 boost::split(tokens, line, boost::is_any_of(
"\t\r "), boost::token_compress_on);
2038 string pcd_version_str;
2039 if (tokens[0] ==
"VERSION")
2043 if (tokens[1] !=
"0.7" && tokens[1] !=
".7")
2044 throw runtime_error(
"PCD Parse Error: Only PCD Version 0.7 is supported");
2047 else if (tokens[0] ==
"FIELDS")
2051 for (
size_t i = 1; i < tokens.size(); i++)
2058 else if (tokens[0] ==
"SIZE")
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");
2063 for (
size_t i = 1; i < tokens.size(); i++)
2065 const unsigned int size = boost::lexical_cast<unsigned int >(tokens[i]);
2071 else if (tokens[0] ==
"TYPE")
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");
2076 for (
size_t i = 1; i < tokens.size(); i++)
2078 const char type = boost::lexical_cast<char>(tokens[i]);
2080 if (type !=
'I' && type !=
'U' && type !=
'F')
2081 throw runtime_error(
"PCD Parse Error: invalid TYPE, it must be 'I', 'U', or 'F'");
2086 else if (tokens[0] ==
"COUNT")
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");
2092 for (
size_t i = 1; i < tokens.size(); i++)
2094 const unsigned int count = boost::lexical_cast<unsigned int >(tokens[i]);
2100 else if (tokens[0] ==
"WIDTH")
2104 header.
width = boost::lexical_cast<unsigned int >(tokens[1]);
2106 catch (boost::bad_lexical_cast&)
2108 throw runtime_error(
"PCD Parse Error: invalid WIDTH");
2113 else if (tokens[0] ==
"HEIGHT")
2117 header.
height= boost::lexical_cast<unsigned int >(tokens[1]);
2119 catch (boost::bad_lexical_cast&)
2121 throw runtime_error(
"PCD Parse Error: invalid HEIGHT");
2126 else if (tokens[0] ==
"VIEWPOINT")
2128 if((tokens.size() - 1) != 7 )
2129 throw runtime_error(
"PCD Parse Error: number of elements for VIEWPOINT must be 7");
2131 for (
size_t i = 1; i < tokens.size(); i++)
2135 header.
viewPoint(i-1, 0) = boost::lexical_cast<T>(tokens[i]);
2137 catch (boost::bad_lexical_cast&)
2140 ss <<
"PCD Parse Error: invalid value(" << tokens[i] <<
") of VIEWPOINT";
2141 throw runtime_error(ss.str());
2147 else if (tokens[0] ==
"POINTS")
2151 header.
nbPoints = boost::lexical_cast<unsigned int>(tokens[1]);
2153 catch (boost::bad_lexical_cast&)
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());
2161 else if (tokens[0] ==
"DATA")
2170 else if(header.
dataType ==
"binary")
2172 throw runtime_error(
"PCD Implementation Error: the option for DATA binary is not implemented yet");
2177 ss <<
"PCD Parse Error: the value in the element DATA (" << tokens[1] <<
") must be ascii or binary";
2178 throw runtime_error(ss.str());
2187 throw runtime_error(
"PCD Parse Error: no FIELDS were find in the header");
2192 throw runtime_error(
"PCD Parse Error: POINTS field does not match WIDTH and HEIGHT fields");
2200 int rowIdFeatures = 0;
2201 int rowIdDescriptors = 0;
2207 for(
size_t i=0; i<externalLabels.size(); i++)
2212 for(
size_t i=0; i < header.
properties.size(); i++)
2223 switch (supLabel.
type)
2226 header.
properties[i].pmRowID = rowIdFeatures;
2232 ss <<
"PCD Parse Error: the field " << prop.
field <<
" must have a count of 1";
2233 throw runtime_error(ss.str());
2237 header.
properties[i].pmRowID = rowIdDescriptors;
2239 rowIdDescriptors += prop.
count;
2244 rowIdTime += prop.
count;
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'"));
2257 for(
size_t i=0; i < header.
properties.size(); i++)
2263 header.
properties[i].pmRowID = rowIdDescriptors;
2265 rowIdDescriptors += prop.
count;
2276 const unsigned int totalDim = featDim + descDim + timeDim;
2277 const unsigned int nbPoints = header.
nbPoints;
2295 if (line.substr(0,1) ==
"#" || line ==
"")
2301 vector<string> tokens;
2302 boost::split(tokens, line, boost::is_any_of(
"\t\r "), boost::token_compress_on);
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));
2308 unsigned int fileCol = 0;
2309 for(
size_t i=0; i<header.
properties.size(); i++)
2311 const unsigned int count = header.
properties[i].count;
2312 const unsigned int row = header.
properties[i].pmRowID;
2316 for(
size_t j=0; j<count; j++)
2321 features(row+j, col) = boost::lexical_cast<T>(tokens[fileCol]);
2324 descriptors(row+j, col) = boost::lexical_cast<T>(tokens[fileCol]);
2327 times(row+j, col) = boost::lexical_cast<std::int64_t>(tokens[fileCol]);
2330 throw runtime_error(
"Implementation error in loadPCD(). This should not throw.");
2343 if (col != nbPoints)
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());
2355 if (descriptors.rows() > 0)
2361 if(times.rows() > 0)
2363 loadedPoints.
times = times;
2370 loadedPoints.
addFeature(
"pad", Matrix::Ones(1,features.cols()));
2373 return loadedPoints;
2376 template<
typename T>
2378 const std::string& fileName,
unsigned precision) {
2379 ofstream ofs(fileName.c_str());
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());
2388 if (pointCount == 0)
2394 ofs <<
"# .PCD v.7 - Point Cloud Data file format\n" <<
"VERSION .7\n";
2397 for (
int f=0; f < (featCount - 1); f++)
2399 ofs <<
" " <<
data.featureLabels[f].text;
2406 for (
int i = 0; i < descCount; i++)
2408 ofs <<
" " <<
data.descriptorLabels[i].text;
2414 for (
int i =0; i < featCount - 1 + descCount; i++)
2421 for (
int i =0; i < featCount - 1 + descCount; i++)
2428 for (
int f = 0; f < featCount - 1 ; f++ )
2434 for (
int i = 0; i < descCount; i++)
2436 ofs <<
" " <<
data.descriptorLabels[i].span;
2441 ofs <<
"WIDTH " << pointCount <<
"\n";
2442 ofs <<
"HEIGHT 1\n";
2443 ofs <<
"POINTS " << pointCount <<
"\n";
2444 ofs <<
"DATA ascii\n";
2447 for (
int p = 0; p < pointCount; ++p)
2449 for (
int f = 0; f < featCount - 1; ++f)
2451 ofs <<
data.features(f, p);
2452 if(!(f == featCount-2 && descRows == 0))
2455 for (
int d = 0; d < descRows; ++d)
2457 ofs <<
data.descriptors(d, p);