UosIO.cpp
Go to the documentation of this file.
1 
35 #include <list>
36 #include <vector>
37 #include <string>
38 #include <iomanip>
39 #include <iostream>
40 #include <cmath>
41 #include <fstream>
42 #include <sstream>
43 
44 using std::list;
45 using std::vector;
46 using std::ifstream;
47 using std::stringstream;
48 
49 #include <boost/filesystem.hpp>
50 
51 #include "lvr2/io/UosIO.hpp"
52 #include "lvr2/io/Progress.hpp"
53 #include "lvr2/io/Timestamp.hpp"
54 
55 namespace lvr2
56 {
57 
58 
59 ModelPtr UosIO::read(string dir)
60 {
61  ModelPtr model;
62 
63  size_t n = 0;
64  boost::filesystem::path directory(dir);
65  if(is_directory(directory))
66  {
67  // Iterate through directory, count relevant objects
68  int n3dFiles = 0;
69 
70  // First and last scan to load
71  int firstScan = -1;
72  int lastScan = -1;
73 
74  boost::filesystem::directory_iterator lastFile;
75 
76  // First, look for .3d files
77  for(boost::filesystem::directory_iterator it(directory); it != lastFile; it++ )
78  {
79  boost::filesystem::path p = it->path();
80  if(p.extension().string() == ".3d")
81  {
82  // Check for naming convention "scanxxx.3d"
83  int num = 0;
84  if(sscanf(p.filename().string().c_str(), "scan%3d", &num))
85  {
86  n3dFiles++;
87  if(firstScan == -1) firstScan = num;
88  if(lastScan == -1) lastScan = num;
89 
90  if(num > lastScan) lastScan = num;
91  if(num < firstScan) firstScan = num;
92  }
93  }
94  }
95 
96  // Check if given directory contains scans in new format.
97  // If so, read them and return result. Otherwise try to
98  // read new format.
99  if(n3dFiles > 0)
100  {
101  // Check for user scan ranges
102  if(m_firstScan > -1 && m_firstScan <= lastScan)
103  {
104  firstScan = m_firstScan;
105  }
106 
107  if(m_lastScan >= -1 && m_lastScan <= lastScan && m_lastScan >= firstScan)
108  {
109  lastScan = m_lastScan;
110  }
111 
112  m_firstScan = firstScan;
113  m_lastScan = lastScan;
114 
115  cout << timestamp << "Reading " << n3dFiles << " scans in UOS format "
116  << "(From " << firstScan << " to " << lastScan << ")." << endl;
117  readNewFormat(model, dir, firstScan, lastScan, n);
118  }
119  else
120  {
121  // Count numbered sub directories, ignore others
122  int nDirs = 0;
123  for(boost::filesystem::directory_iterator it(directory); it != lastFile; it++ )
124  {
125  boost::filesystem::path p = it->path();
126  int num = 0;
127 
128  // Only count numbered dirs
129  if(sscanf(p.filename().string().c_str(), "%d", &num))
130  {
131  if(firstScan == -1) firstScan = num;
132  if(lastScan == -1) lastScan = num;
133 
134 
135  if(num > lastScan) lastScan = num;
136  if(num < firstScan) firstScan = num;
137 
138  nDirs++;
139  }
140  }
141 
142  // Check is dirs were found and try to read old format
143  if(nDirs)
144  {
145  // Check for user scan ranges
146  if(m_firstScan > -1 && m_firstScan <= lastScan)
147  {
148  firstScan = m_firstScan;
149  }
150 
151  if(m_lastScan >= -1 && m_lastScan <= lastScan && m_lastScan >= firstScan)
152  {
153  lastScan = m_lastScan;
154  }
155 
156  m_firstScan = firstScan;
157  m_lastScan = lastScan;
158 
159  cout << timestamp << "Reading " << nDirs << " scans in old UOS format "
160  << "(From " << firstScan << " to " << lastScan << ")." << endl;
161  readOldFormat(model, dir, firstScan, lastScan, n);
162  }
163  else
164  {
165  return ModelPtr();
166  }
167  }
168 
169  }
170  else
171  {
172  cout << timestamp << "UOSReader: " << dir << " is not a directory." << endl;
173  }
174 
175  m_model = model;
176  return model;
177 }
178 
179 
180 void UosIO::reduce(string dir, string target, int reduction)
181 {
182  // Open output stream
183  m_outputFile.open(target.c_str());
184  if(!m_outputFile.good())
185  {
186  cout << timestamp << "UOSReader: " << dir << " unable to open " << target << " for writing." << endl;
187  return;
188  }
189 
190  // Set needed flags for inout code
191  m_reductionTarget = reduction;
192  m_saveToDisk = true;
193 
194  // Read data and write reduced points
195  ModelPtr m = read(dir);
196 
197 
198 }
199 
200 
201 void UosIO::readNewFormat(ModelPtr &model, string dir, int first, int last, size_t &n)
202 {
203  list<Vec > allPoints;
204  list<BaseVector<int> > allColors;
205 
206  size_t point_counter = 0;
207 
208  vector<indexPair> sub_clouds;
209 
210  // Count points in all given files
211  size_t numPointsTotal = 0;
212  for(int fileCounter = first; fileCounter <= last; fileCounter++)
213  {
214  // Create scan file name
215  boost::filesystem::path scan_path(
216  boost::filesystem::path(dir) /
217  boost::filesystem::path( "scan" + to_string( fileCounter, 3 ) + ".3d" ) );
218  string scanFileName = "/" + scan_path.relative_path().string();
219 
220  // Count lines in scan
221  numPointsTotal += AsciiIO::countLines(scanFileName);
222  }
223 
224  // Calculate the number of points to skip when writing to disk
225  size_t skipPoints = 1;
226 
227  if(m_reductionTarget > 1)
228  {
229  skipPoints = (int)numPointsTotal / m_reductionTarget;
230  }
231 
232  if(m_saveToDisk)
233  {
234  cout << timestamp << "Reduction mode. Writing every " << skipPoints << "th point." << endl;
235  }
236 
237  for(int fileCounter = first; fileCounter <= last; fileCounter++)
238  {
239  // New (unit) transformation matrix
240  Matrix4<Vec> tf;
241 
242  // Input file streams for scan data, poses and frames
243  ifstream scan_in, pose_in, frame_in;
244 
245  // Create scan file name
246  boost::filesystem::path scan_path(
247  boost::filesystem::path(dir) /
248  boost::filesystem::path( "scan" + to_string( fileCounter, 3 ) + ".3d" ) );
249  string scanFileName = scan_path.string();
250 
251  // Count lines in scan
252  size_t points_in_file = AsciiIO::countLines(scanFileName);
253 
254  int num_attributes = AsciiIO::getEntriesInLine(scanFileName) - 3;
255  bool has_color = (num_attributes == 3) || (num_attributes == 4);
256  bool has_intensity = (num_attributes == 1) || (num_attributes == 4);
257 
258  if(has_color)
259  {
260  cout << timestamp << "Reading color information." << endl;
261  }
262 
263  if(has_intensity)
264  {
265  cout << timestamp << "Reading intensity information." << endl;
266  }
267 
268  // Read scan data
269  scan_in.open(scanFileName.c_str());
270  if(!scan_in.good())
271  {
272  // Continue with next file if the expected file couldn't be read
273  cout << timestamp << "UOS Reader: Unable to read scan " << scanFileName << endl;
274  scan_in.close();
275  scan_in.clear();
276  continue;
277  }
278  else
279  {
280  // Tmp list of read points
281  list<Vec > tmp_points;
282 
283 
284  // Try to get fransformation from .frames file
285  boost::filesystem::path frame_path(
286  boost::filesystem::path(dir) /
287  boost::filesystem::path( "scan" + to_string( fileCounter, 3 ) + ".frames" ) );
288  string frameFileName = frame_path.string();
289 
290  frame_in.open(frameFileName.c_str());
291  if(!frame_in.good())
292  {
293  // Try to parse .pose file
294  boost::filesystem::path pose_path(
295  boost::filesystem::path(dir) /
296  boost::filesystem::path( "scan" + to_string( fileCounter, 3 ) + ".pose" ) );
297  string poseFileName = pose_path.string();
298 
299  pose_in.open(poseFileName.c_str());
300  if(pose_in.good())
301  {
302  float euler[6];
303  for(int i = 0; i < 6; i++) pose_in >> euler[i];
304 
305  euler[3] *= 0.017453293;
306  euler[4] *= 0.017453293;
307  euler[5] *= 0.017453293;
308 
309  Vec position(euler[0], euler[1], euler[2]);
310  Vec angle(euler[3], euler[4], euler[5]);
311 
312  tf = Matrix4<Vec>(position, angle);
313  }
314  else
315  {
316  cout << timestamp << "UOS Reader: Warning: No position information found." << endl;
317  tf = Matrix4<Vec>();
318  }
319 
320  }
321  else
322  {
323  // Use transformation from .frame files
324  tf = parseFrameFile(frame_in);
325 
326  }
327 
328  // Print pose information
329  float euler[6];
330  tf.toPostionAngle(euler);
331 
332  cout << timestamp << "Processing " << scanFileName << " @ "
333  << euler[0] << " " << euler[1] << " " << euler[2] << " "
334  << euler[3] << " " << euler[4] << " " << euler[5] << endl;
335 
336  // Skip first line in scan file (maybe metadata)
337  char dummy[1024];
338  scan_in.getline(dummy, 1024);
339 
340  // Setup info output
341  string comment = timestamp.getElapsedTime() + "Reading file " + scanFileName;
342  ProgressBar progress(points_in_file, comment);
343 
344  // Read all points
345  while(scan_in.good())
346  {
347  float x, y, z, rem, dummy;
348  int r, g, b;
349 
350  point_counter ++;
351 
352  if(has_intensity && !has_color)
353  {
354  scan_in >> x >> y >> z >> rem;
355  }
356  else if(has_intensity && has_color)
357  {
358  scan_in >> x >> y >> z >> rem >> r >> g >> b;
359  allColors.push_back(BaseVector<int> (r, g, b));
360  }
361  else if(has_color && !has_intensity)
362  {
363  scan_in >> x >> y >> z >> r >> g >> b;
364  allColors.push_back(BaseVector<int> (r, g, b));
365  }
366  else
367  {
368  scan_in >> x >> y >> z;
369  for(int n_dummys = 0; n_dummys < num_attributes; n_dummys++) scan_in >> dummy;
370  }
371 
372  BaseVector<float> point(x, y, z);
374 
375  // Code branching for point converter!
376  if(!m_saveToDisk)
377  {
378  tmp_points.push_back(point);
379  }
380  else
381  {
382  if(m_outputFile.good())
383  {
384  if(point_counter % skipPoints == 0)
385  {
386  point = tf * point;
387  m_outputFile << point[0] << " " << point[1] << " " << point[2] << " ";
388 
389  // Save remission values if present
390  if(has_intensity && m_saveRemission)
391  {
392  m_outputFile << rem << " ";
393  }
394 
395  // Save color values if present
396  if(has_color)
397  {
398  m_outputFile << r << " " << g << " " << b;
399  }
400  else if(m_saveRemissionColor)
401  {
402  r = g = b = rem;
403  m_outputFile << r << " " << g << " " << b;
404  }
405  m_outputFile << endl;
406  }
407  }
408  }
409  ++progress;
410  }
411 
412  // Save index of first point of new scan
413  size_t firstIndex;
414  if(allPoints.size() > 0)
415  {
416  firstIndex = allPoints.size();
417  }
418  else
419  {
420  firstIndex = 0;
421  }
422 
423  // Transform scan point with current matrix
424  list<Vec >::iterator it, it1;
425  for(it = tmp_points.begin(); it != tmp_points.end(); it++)
426  {
427  Vec v = *it;
428  v = tf * v;
429  allPoints.push_back(v);
430  }
431 
432  // Save last index
433  size_t lastIndex;
434  if(allPoints.size() > 0)
435  {
436  lastIndex = allPoints.size() - 1;
437  }
438  else
439  {
440  lastIndex = 0;
441  }
442 
443  // Save index pair for current scan
444  sub_clouds.push_back(make_pair(firstIndex, lastIndex));
445  m_numScans++;
446  }
447  cout << endl;
448  }
449 
450  // Convert into array
451  if ( allPoints.size() )
452  {
453  cout << timestamp << "UOS Reader: Read " << allPoints.size() << " points." << endl;
454 
455  // Save position information
456 
457  size_t numPoints(0);
458  floatArr points;
459  ucharArr pointColors;
460 
461 
462  numPoints = allPoints.size();
463  points = floatArr( new float[3 * allPoints.size()] );
464  list<Vec >::iterator p_it;
465  size_t i(0);
466  for( p_it = allPoints.begin(); p_it != allPoints.end(); p_it++ )
467  {
468  Vec v = *p_it;
469  points[i ] = v[0];
470  points[i + 1] = v[1];
471  points[i + 2] = v[2];
472  i += 3;
473  }
474 
475  // Save color information
476  if ( allColors.size() )
477  {
478  pointColors = ucharArr( new unsigned char[ 3 * numPoints ] );
479  i = 0;
480  list<BaseVector<int>>::iterator c_it;
481  for(c_it = allColors.begin(); c_it != allColors.end(); c_it++)
482  {
483  BaseVector<int> v = *c_it;
484  pointColors[i ] = (unsigned char) v[0];
485  pointColors[i + 1] = (unsigned char) v[1];
486  pointColors[i + 2] = (unsigned char) v[2];
487  i += 3;
488  }
489  }
490 
491  // Create point cloud in model
492  model = ModelPtr( new Model );
493  model->m_pointCloud = PointBufferPtr( new PointBuffer );
494  model->m_pointCloud->setPointArray( points, numPoints );
495 
496  if (allColors.size())
497  {
498  model->m_pointCloud->setColorArray(pointColors, numPoints);
499  }
500 
501  // Add sub cloud information
502  if (sub_clouds.size())
503  {
504  indexArray sub_clouds_array = indexArray( new unsigned int[sub_clouds.size() * 2] );
505  for(size_t i = 0; i < sub_clouds.size(); i++)
506  {
507  sub_clouds_array[i*2 + 0] = sub_clouds[i].first;
508  sub_clouds_array[i*2 + 1] = sub_clouds[i].second;
509  }
510 
511  model->m_pointCloud->addIndexChannel(sub_clouds_array, "sub_clouds", numPoints, 2);
512  }
513  }
514 
515 }
516 
517 void UosIO::readOldFormat(ModelPtr &model, string dir, int first, int last, size_t &n)
518 {
519  Matrix4<Vec> m_tf;
520 
521  list<Vec > ptss;
522  list<Vec > allPoints;
523  for(int fileCounter = first; fileCounter <= last; fileCounter++)
524  {
525  float euler[6];
526  ifstream scan_in, pose_in, frame_in;
527 
528  // Code imported from slam6d! Don't blame me..
529  string scanFileName;
530  string poseFileName;
531 
532  // Create correct path
533  boost::filesystem::path p(
534  boost::filesystem::path(dir) /
535  boost::filesystem::path( to_string( fileCounter, 3 ) ) /
536  boost::filesystem::path( "position.dat" ) );
537 
538  // Get file name (if some knows a more elegant way to
539  // extract the pull path let me know
540  poseFileName = "/" + p.relative_path().string();
541 
542  // Try to open file
543  pose_in.open(poseFileName.c_str());
544 
545  // Abort if opening failed and try with next die
546  if (!pose_in.good()) continue;
547  cout << timestamp << "Processing Scan " << dir << "/" << to_string(fileCounter, 3) << endl;
548 
549  // Extract pose information
550  for (unsigned int i = 0; i < 6; pose_in >> euler[i++]);
551 
552  // Convert mm to cm
553  for (unsigned int i = 0; i < 3; i++) euler[i] = euler[i] * 0.1;
554 
555  // Convert angles from deg to rad
556  for (unsigned int i = 3; i <= 5; i++) {
557  euler[i] *= 0.01f;
558  // if (euler[i] < 0.0) euler[i] += 360;
559  euler[i] = rad(euler[i]);
560  }
561 
562  // Read and convert scan
563  for (int i = 1; ; i++) {
564  //scanFileName = dir + to_string(fileCounter, 3) + "/scan" + to_string(i,3) + ".dat";
565 
566  boost::filesystem::path sfile(
567  boost::filesystem::path(dir) /
568  boost::filesystem::path( to_string( fileCounter, 3 ) ) /
569  boost::filesystem::path( "scan" + to_string(i) + ".dat" ) );
570  scanFileName = "/" + sfile.relative_path().string();
571 
572  scan_in.open(scanFileName.c_str());
573  if (!scan_in.good()) {
574  scan_in.close();
575  scan_in.clear();
576  break;
577  }
578 
579 
580  int Nr = 0, intensity_flag = 0;
581  int D;
582  double current_angle;
583  double X, Z, I; // x,z coordinate and intensity
584 
585  char firstLine[81];
586  scan_in.getline(firstLine, 80);
587 
588  char cNr[4];
589  cNr[0] = firstLine[2];
590  cNr[1] = firstLine[3];
591  cNr[2] = firstLine[4];
592  cNr[3] = 0;
593  Nr = atoi(cNr);
594 
595  // determine weather we have the new files with intensity information
596  if (firstLine[16] != 'i') {
597  intensity_flag = 1;
598  char cAngle[8];
599  cAngle[0] = firstLine[35];
600  cAngle[1] = firstLine[36];
601  cAngle[2] = firstLine[37];
602  cAngle[3] = firstLine[38];
603  cAngle[4] = firstLine[39];
604  cAngle[5] = firstLine[40];
605  cAngle[6] = firstLine[41];
606  cAngle[7] = 0;
607  current_angle = atof(cAngle);
608  cout << current_angle << endl;
609  } else {
610  intensity_flag = 0;
611  char cAngle[8];
612  cAngle[0] = firstLine[54];
613  cAngle[1] = firstLine[55];
614  cAngle[2] = firstLine[56];
615  cAngle[3] = firstLine[57];
616  cAngle[4] = firstLine[58];
617  cAngle[5] = firstLine[59];
618  cAngle[6] = firstLine[60];
619  cAngle[7] = 0;
620  current_angle = atof(cAngle);
621  }
622 
623  double cos_currentAngle = cos(rad(current_angle));
624  double sin_currentAngle = sin(rad(current_angle));
625 
626  for (int j = 0; j < Nr; j++) {
627  if (!intensity_flag) {
628  scan_in >> X >> Z >> D >> I;
629  } else {
630  scan_in >> X >> Z;
631  I = 1.0;
632  }
633 
634  // calculate 3D coordinates (local coordinates)
635  Vec p;
636  p[0] = X;
637  p[1] = Z * sin_currentAngle;
638  p[2] = Z * cos_currentAngle;
639 
640  ptss.push_back(p);
641  }
642  scan_in.close();
643  scan_in.clear();
644  }
645 
646  pose_in.close();
647  pose_in.clear();
648 
649  // Create path to frame file
650  boost::filesystem::path framePath(
651  boost::filesystem::path(dir) /
652  boost::filesystem::path("scan" + to_string( fileCounter, 3 ) + ".frames" ) );
653  string frameFileName = "/" + framePath.relative_path().string();
654 
655  // Try to open frame file
656  frame_in.open(frameFileName.c_str());
657  if(frame_in.good())
658  {
659  // Transform scan data according to frame file
660  m_tf = parseFrameFile(frame_in);
661  }
662  else
663  {
664  // Transform scan data using information from 'position.dat'
665  Vec position(euler[0], euler[1], euler[2]);
666  Vec angle(euler[3], euler[4], euler[5]);
667  m_tf = Matrix4<Vec>(position, angle);
668  }
669 
670  // Transform points and insert in to global vector
671  list<Vec >::iterator it;
672  for(it = ptss.begin(); it != ptss.end(); it++)
673  {
674  Vec v = *it;
675  v = m_tf * v;
676  allPoints.push_back(v);
677  }
678 
679  // Clear scan
680  ptss.clear();
681  }
682 
683  // Convert into indexed array
684  if(allPoints.size() > 0)
685  {
686  cout << timestamp << "UOS Reader: Read " << allPoints.size() << " points." << endl;
687  n = allPoints.size();
688  floatArr points( new float[3 * allPoints.size()] );
689  list<Vec >::iterator p_it;
690  int i(0);
691  for( p_it = allPoints.begin(); p_it != allPoints.end(); p_it++ )
692  {
693  int t_index = 3 * i;
694  Vec v = *p_it;
695  points[t_index ] = v[0];
696  points[t_index + 1] = v[1];
697  points[t_index + 2] = v[2];
698  i++;
699  }
700 
701  // Alloc model
702  model = ModelPtr( new Model );
703  model->m_pointCloud = PointBufferPtr( new PointBuffer );
704  model->m_pointCloud->setPointArray( points, n );
705  }
706 }
707 
709 {
710  float m[16], color;
711  while(frameFile.good())
712  {
713  for(int i = 0; i < 16; i++ && frameFile.good()) frameFile >> m[i];
714  frameFile >> color;
715  }
716 
717  return Matrix4<Vec>(m);
718 }
719 
720 } // namespace lvr2
lvr2::floatArr
boost::shared_array< float > floatArr
Definition: DataStruct.hpp:133
lvr2::ProgressBar
Definition: Progress.hpp:68
lvr2::UosIO::m_saveRemissionColor
bool m_saveRemissionColor
If true, remission values will be converted to color.
Definition: UosIO.hpp:239
lvr2::Matrix4
A 4x4 matrix class implementation for use with the provided vertex types.
Definition: Matrix4.hpp:64
lvr2::BaseVector< float >
lvr2::UosIO::readOldFormat
void readOldFormat(ModelPtr &m, string dir, int first, int last, size_t &n)
Reads scans from first} to last} in old UOS format.
Definition: UosIO.cpp:517
lvr2::UosIO::m_reductionTarget
int m_reductionTarget
Number of targeted points for reduction.
Definition: UosIO.hpp:236
lvr2::UosIO::m_saveRemission
bool m_saveRemission
If true, the original remission information will be saved.
Definition: UosIO.hpp:242
lvr2::indexArray
boost::shared_array< unsigned int > indexArray
Definition: DataStruct.hpp:128
lvr2::UosIO::m_firstScan
int m_firstScan
The first scan to read (or -1 if all scans should be processed)
Definition: UosIO.hpp:221
lvr2::color
Definition: DataStruct.hpp:81
lvr2::PointBufferPtr
std::shared_ptr< PointBuffer > PointBufferPtr
Definition: PointBuffer.hpp:130
lvr2::UosIO::m_lastScan
int m_lastScan
The last scan to read (or -1 if all scans should be processed)
Definition: UosIO.hpp:224
lvr2::UosIO::m_saveToDisk
bool m_saveToDisk
If true, the read point will not be stored in local memory.
Definition: UosIO.hpp:227
lvr2::AsciiIO::getEntriesInLine
static int getEntriesInLine(string filename)
Helper method. Returns the number of columns in the given file.
Definition: AsciiIO.cpp:404
p
SharedPointer p
Definition: ConvertShared.hpp:42
lvr2::PointBuffer
A class to handle point information with an arbitrarily large number of attribute channels....
Definition: PointBuffer.hpp:51
lvr2::Timestamp::getElapsedTime
string getElapsedTime() const
Returns a string representation of the current timer value.
Definition: Timestamp.cpp:136
lvr2::UosIO::reduce
void reduce(string dir, string target, int reduction=1)
Definition: UosIO.cpp:180
lvr2::Model
Definition: Model.hpp:51
lvr2::UosIO::rad
float rad(const float deg)
Definition: UosIO.hpp:202
lvr2::UosIO::to_string
std::string to_string(const int &t, int width)
Definition: UosIO.hpp:177
UosIO.hpp
lvr2::AsciiIO::countLines
static size_t countLines(string filename)
TODO: Coordinate mapping for ascii files.
Definition: AsciiIO.cpp:386
lvr2::timestamp
static Timestamp timestamp
A global time stamp object for program runtime measurement.
Definition: Timestamp.hpp:116
lvr2::UosIO::m_numScans
int m_numScans
Number of loaded scans.
Definition: UosIO.hpp:233
Progress.hpp
lvr2::UosIO::parseFrameFile
Matrix4< Vec > parseFrameFile(ifstream &frameFile)
Creates a transformation matrix from given frame file.
Definition: UosIO.cpp:708
lvr2::BaseIO::m_model
ModelPtr m_model
Definition: BaseIO.hpp:104
lvr2::ucharArr
boost::shared_array< unsigned char > ucharArr
Definition: DataStruct.hpp:137
lvr2
Definition: BaseBufferManipulators.hpp:39
lvr2::ModelPtr
std::shared_ptr< Model > ModelPtr
Definition: Model.hpp:80
lvr2::Matrix4::toPostionAngle
void toPostionAngle(ValueType pose[6])
Computes an Euler representation (x, y, z) plus three rotation values in rad. Rotations are with resp...
Definition: Matrix4.hpp:433
Timestamp.hpp
lvr2::UosIO::readNewFormat
void readNewFormat(ModelPtr &m, string dir, int first, int last, size_t &n)
Reads scans from first} to last} in new UOS format.
Definition: UosIO.cpp:201
first
void first(int id)
Definition: example.cpp:7
lvr2::UosIO::m_outputFile
ofstream m_outputFile
Filestream to save reduced data.
Definition: UosIO.hpp:230
lvr2::UosIO::read
ModelPtr read(string dir)
Reads all scans or an specified range of scans from the given directory.
Definition: UosIO.cpp:59


lvr2
Author(s): Thomas Wiemann , Sebastian Pütz , Alexander Mock , Lars Kiesow , Lukas Kalbertodt , Tristan Igelbrink , Johan M. von Behren , Dominik Feldschnieders , Alexander Löhr
autogenerated on Wed Mar 2 2022 00:37:25