50 #include <boost/filesystem.hpp> 51 #include <opencv2/opencv.hpp> 61 std::cerr <<
timestamp <<
"No data to save." << std::endl;
79 size_t w_point_color = 0;
80 size_t w_vertex_color = 0;
81 size_t m_numVertices = 0;
82 size_t m_numVertexColors = 0;
83 size_t m_numVertexConfidences = 0;
84 size_t m_numVertexIntensities = 0;
85 size_t m_numVertexNormals = 0;
87 size_t m_numPoints = 0;
88 size_t m_numPointColors = 0;
89 size_t m_numPointConfidence = 0;
90 size_t m_numPointIntensities = 0;
91 size_t m_numPointNormals = 0;
92 size_t m_numFaces = 0;
103 m_numPoints = pc->numPoints();
104 m_numPointNormals = m_numPoints;
105 m_numPointColors = m_numPoints;
107 m_points = pc->getPointArray();
108 m_pointConfidences = pc->getFloatArray(
"confidences", m_numPointConfidence, dummy);
109 m_pointColors = pc->getColorArray(w_point_color);
110 m_pointIntensities = pc->getFloatArray(
"intensities", m_numPointIntensities, dummy);
111 m_pointNormals = pc->getNormalArray();
117 m_numVertices = mesh->numVertices();
118 m_numFaces = mesh->numFaces();
119 m_numVertexColors = m_numVertices;
120 m_numVertexNormals = m_numVertices;
122 m_vertices = mesh->getVertices();
123 m_vertexColors = mesh->getVertexColors(w_vertex_color);
124 m_vertexConfidence = mesh->getFloatArray(
"vertex_confidences", m_numVertexConfidences, dummy);
125 m_vertexIntensity = mesh->getFloatArray(
"vertex_intensities", m_numVertexIntensities, dummy);
126 m_vertexNormals = mesh->getVertexNormals();
127 m_faceIndices = mesh->getFaceIndices();
134 std::cerr <<
timestamp <<
"Could not create »" << filename <<
"«" << std::endl;
139 if ( !( m_vertices || m_points ) )
141 std::cout <<
timestamp <<
"Neither vertices nor points to write." << std::endl;
144 std::cerr <<
timestamp <<
"Could not close file." << std::endl;
151 bool vertex_color =
false;
152 bool vertex_intensity =
false;
153 bool vertex_confidence =
false;
154 bool vertex_normal =
false;
155 bool point_color =
false;
156 bool point_intensity =
false;
157 bool point_confidence =
false;
158 bool point_normal =
false;
172 if ( m_vertexColors )
174 if ( m_numVertexColors != m_numVertices )
176 std::cerr <<
timestamp <<
"Amount of vertices and color information is" 177 <<
" not equal. Color information won't be written." << std::endl;
189 if ( m_vertexIntensity )
191 if ( m_numVertexIntensities != m_numVertices )
193 std::cout <<
timestamp <<
"Amount of vertices and intensity" 194 <<
" information is not equal. Intensity information won't be" 195 <<
" written." << std::endl;
200 vertex_intensity =
true;
205 if ( m_vertexConfidence )
207 if ( m_numVertexConfidences != m_numVertices )
209 std::cout <<
timestamp <<
"Amount of vertices and confidence" 210 <<
" information is not equal. Confidence information won't be" 211 <<
" written." << std::endl;
216 vertex_confidence =
true;
221 if ( m_vertexNormals )
223 if ( m_numVertexNormals != m_numVertices )
225 std::cout <<
timestamp <<
"Amount of vertices and normals" 226 <<
" does not match. Normals won't be written." << std::endl;
233 vertex_normal =
true;
258 if ( m_numPointColors != m_numPoints )
260 std::cout <<
timestamp <<
"Amount of points and color information is" 261 <<
" not equal. Color information won't be written." << std::endl;
273 if ( m_pointIntensities )
275 if ( m_numPointIntensities != m_numPoints )
277 std::cout <<
timestamp <<
"Amount of points and intensity" 278 <<
" information is not equal. Intensity information won't be" 279 <<
" written." << std::endl;
284 point_intensity =
true;
289 if ( m_pointConfidences )
291 if ( m_numPointConfidence != m_numPoints )
293 std::cout <<
timestamp <<
"Amount of point and confidence" 294 <<
" information is not equal. Confidence information won't be" 295 <<
" written." << std::endl;
300 point_confidence =
true;
305 if ( m_pointNormals )
307 if ( m_numPointNormals != m_numPoints )
309 std::cout <<
timestamp <<
"Amount of point and normals does" 310 <<
" not match. Normals won't be written." << std::endl;
325 std::cerr <<
timestamp <<
"Could not write header." << std::endl;
331 for (
size_t i = 0; i < m_numVertices; i++ )
333 ply_write( oply, (
double) m_vertices[ i * 3 ] );
334 ply_write( oply, (
double) m_vertices[ i * 3 + 1 ] );
335 ply_write( oply, (
double) m_vertices[ i * 3 + 2 ] );
338 ply_write( oply, m_vertexColors[ i * w_vertex_color ] );
339 ply_write( oply, m_vertexColors[ i * w_vertex_color + 1 ] );
340 ply_write( oply, m_vertexColors[ i * w_vertex_color + 2 ] );
342 if ( vertex_intensity )
344 ply_write( oply, m_vertexIntensity[ i ] );
346 if ( vertex_confidence )
348 ply_write( oply, m_vertexConfidence[ i ] );
352 ply_write( oply, (
double) m_vertexNormals[ i * 3 ] );
353 ply_write( oply, (
double) m_vertexNormals[ i * 3 + 1 ] );
354 ply_write( oply, (
double) m_vertexNormals[ i * 3 + 2 ] );
361 for (
size_t i = 0; i < m_numFaces; i++ )
364 ply_write( oply, (
double) m_faceIndices[ i * 3 ] );
365 ply_write( oply, (
double) m_faceIndices[ i * 3 + 1 ] );
366 ply_write( oply, (
double) m_faceIndices[ i * 3 + 2 ] );
370 for (
size_t i = 0; i < m_numPoints; i++ )
372 ply_write( oply, (
double) m_points[ i * 3 ] );
373 ply_write( oply, (
double) m_points[ i * 3 + 1 ] );
374 ply_write( oply, (
double) m_points[ i * 3 + 2 ] );
377 ply_write( oply, m_pointColors[ i * w_point_color ] );
378 ply_write( oply, m_pointColors[ i * w_point_color + 1 ] );
379 ply_write( oply, m_pointColors[ i * w_point_color + 2 ] );
381 if ( point_intensity )
383 ply_write( oply, m_pointIntensities[ i ] );
385 if ( point_confidence )
387 ply_write( oply, m_pointConfidences[ i ] );
391 ply_write( oply, (
double) m_pointNormals[ i * 3 ] );
392 ply_write( oply, (
double) m_pointNormals[ i * 3 + 1 ] );
393 ply_write( oply, (
double) m_pointNormals[ i * 3 + 2 ] );
399 std::cerr <<
timestamp <<
"Could not close file." << std::endl;
407 return read( filename,
true );
413 template <
typename T>
414 void swap(T*& arr,
size_t i1,
size_t i2,
size_t n)
416 std::swap_ranges(arr + i1, arr + i1 + n, arr + i2);
420 bool readIntensity,
bool readNormals,
bool readFaces,
bool readPanoramaCoords )
428 std::cerr <<
timestamp <<
"Could not open »" << filename <<
"«." 434 std::cerr <<
timestamp <<
"Could not read header." << std::endl;
441 const char * name = buf;
446 size_t numVertices = 0;
447 size_t numVertexColors = 0;
448 size_t numVertexConfidences = 0;
449 size_t numVertexIntensities = 0;
450 size_t numVertexNormals = 0;
451 size_t numVertexPanoramaCoords = 0;
453 size_t numPoints = 0;
454 size_t numPointColors = 0;
455 size_t numPointConfidence = 0;
456 size_t numPointIntensities = 0;
457 size_t numPointNormals = 0;
458 size_t numPointPanoramaCoords = 0;
459 size_t numPointSpectralChannels = 0;
462 size_t n_channels = 0;
468 if ( !strcmp( name,
"vertex" ) )
475 if ( !strcmp( name,
"red" ) && readColor )
480 else if ( !strcmp( name,
"confidence" ) && readConfidence )
483 numVertexConfidences = n;
485 else if ( !strcmp( name,
"intensity" ) && readIntensity )
488 numVertexIntensities = n;
490 else if ( !strcmp( name,
"nx" ) && readNormals )
493 numVertexNormals = n;
495 else if ( !strcmp( name,
"x_coords" ) && readPanoramaCoords )
498 numVertexPanoramaCoords = n;
502 else if ( !strcmp( name,
"point" ) )
509 if ( !strcmp( name,
"red" ) && readColor )
514 else if ( !strcmp( name,
"confidence" ) && readConfidence )
517 numPointConfidence = n;
519 else if ( !strcmp( name,
"intensity" ) && readIntensity )
522 numPointIntensities = n;
524 else if ( !strcmp( name,
"nx" ) && readNormals )
529 else if ( !strcmp( name,
"x_coords" ) && readPanoramaCoords )
532 numPointPanoramaCoords = n;
536 else if ( !strcmp( name,
"face" ) && readFaces )
542 if ( !( numVertices || numPoints ) )
544 std::cout <<
timestamp <<
"Neither vertices nor points in ply." 572 vertices =
floatArr(
new float[ numVertices * 3 ] );
574 if ( numVertexColors )
576 vertexColors =
ucharArr(
new unsigned char[ numVertices * 3 ] );
578 if ( numVertexConfidences )
580 vertexConfidence =
floatArr(
new float[ numVertices ] );
582 if ( numVertexIntensities )
584 vertexIntensity =
floatArr(
new float[ numVertices ] );
586 if ( numVertexNormals )
588 vertexNormals =
floatArr(
new float[ numVertices * 3 ] );
590 if ( numVertexPanoramaCoords )
592 vertexPanoramaCoords =
shortArr(
new short[ numVertices * 2 ] );
596 faceIndices =
indexArray(
new unsigned int[ numFaces * 3 ] );
600 points =
floatArr(
new float[ numPoints * 3 ] );
602 if ( numPointColors )
604 pointColors =
ucharArr(
new unsigned char[ numPoints * 3 ] );
606 if ( numPointConfidence )
608 pointConfidences =
floatArr(
new float[numPoints] );
610 if ( numPointIntensities )
612 pointIntensities =
floatArr(
new float[numPoints] );
614 if ( numPointNormals )
616 pointNormals =
floatArr(
new float[ numPoints * 3 ] );
618 if ( numPointPanoramaCoords )
620 pointPanoramaCoords =
shortArr(
new short[ numPoints * 2 ] );
624 float* vertex = vertices.get();
625 uint8_t* vertex_color = vertexColors.get();
626 float* vertex_confidence = vertexConfidence.get();
627 float* vertex_intensity = vertexIntensity.get();
628 float* vertex_normal = vertexNormals.get();
629 short* vertex_panorama_coords = vertexPanoramaCoords.get();
630 unsigned int* face = faceIndices.get();
631 float* point = points.get();
632 uint8_t* point_color = pointColors.get();
633 float* point_confidence = pointConfidences.get();
634 float* point_intensity = pointIntensities.get();
635 float* point_normal = pointNormals.get();
636 short* point_panorama_coords = pointPanoramaCoords.get();
652 if ( vertex_confidence )
656 if ( vertex_intensity )
666 if ( vertex_panorama_coords )
690 if ( point_confidence )
694 if ( point_intensity )
704 if ( point_panorama_coords )
713 std::cerr <<
timestamp <<
"Could not read »" << filename <<
"«." 719 if ( vertices && !points && !faceIndices )
721 std::cout <<
timestamp <<
"PLY contains neither faces nor points. " 722 <<
"Assuming that vertices are meant to be points." << std::endl;
724 pointColors = vertexColors;
725 pointConfidences = vertexConfidence;
726 pointIntensities = vertexIntensity;
727 pointNormals = vertexNormals;
728 pointPanoramaCoords = vertexPanoramaCoords;
729 point = points.get();
730 point_color = pointColors.get();
731 point_confidence = pointConfidences.get();
732 point_intensity = pointIntensities.get();
733 point_normal = pointNormals.get();
734 point_panorama_coords = pointPanoramaCoords.get();
735 numPoints = numVertices;
736 numPointColors = numVertexColors;
737 numPointConfidence = numVertexConfidences;
738 numPointIntensities = numVertexIntensities;
739 numPointNormals = numVertexNormals;
740 numPointPanoramaCoords = numVertexPanoramaCoords;
743 numVertexConfidences = 0;
744 numVertexIntensities = 0;
745 numVertexNormals = 0;
746 numVertexPanoramaCoords = 0;
748 vertexColors.reset();
749 vertexConfidence.reset();
750 vertexIntensity.reset();
751 vertexNormals.reset();
752 vertexPanoramaCoords.reset();
758 if (numPointPanoramaCoords)
761 for (
int i = 0; i < numPointPanoramaCoords; i++)
763 if (point_panorama_coords[2 * i] == -1)
766 numPointPanoramaCoords--;
768 const int n = numPointPanoramaCoords;
769 swap(point_panorama_coords, 2 * i, 2 * numPointPanoramaCoords, 2);
770 swap(point, 3 * i, 3 * numPointPanoramaCoords, 3);
771 if (numPointColors)
swap(point_color, 3*i, 3*numPointPanoramaCoords, 3);
772 if (numPointConfidence)
swap(point_confidence, i, numPointPanoramaCoords, 1);
773 if (numPointIntensities)
swap(point_intensity, i, numPointPanoramaCoords, 1);
774 if (numPointNormals)
swap(point_normal, 3*i, 3*numPointPanoramaCoords, 3);
780 std::cout <<
timestamp << numPoints <<
"Found " << (numPoints - numPointPanoramaCoords) <<
" without spectral data. Reodering..." << std::endl;
783 size_t pos_underscore = filename.find_last_of(
"_");
784 size_t pos_extension = filename.find_last_of(
".");
785 string scanNr = filename.substr(pos_underscore + 1, pos_extension - pos_underscore - 1);
787 string channelDirName = string(
"panorama_channels_") + scanNr;
789 boost::filesystem::path dir(filename);
790 dir = dir.parent_path() /
"panoramas_fixed" / channelDirName;
792 if (!boost::filesystem::exists(dir /
"channel0.png"))
794 std::cerr <<
timestamp <<
"Annotated Data given, but " + dir.string() +
" does not contain channel files" << std::endl;
798 std::cout <<
timestamp <<
"Found Annotated Data. Loading spectral channel images from: " << dir.string() <<
"/" << std::endl;
799 std::cout <<
timestamp <<
"This may take a while depending on data size" << std::endl;
801 std::vector<cv::Mat> imgs;
802 std::vector<unsigned char*> pixels;
804 cv::VideoCapture images(dir.string() +
"/channel%d.png");
805 cv::Mat img, imgFlipped;
806 while (images.read(img))
808 imgs.push_back(cv::Mat());
809 cv::flip(img, imgFlipped, 0);
810 cv::cvtColor(imgFlipped, imgs.back(), cv::COLOR_RGB2GRAY);
811 pixels.push_back(imgs.back().data);
814 n_channels = imgs.size();
815 int width = imgs[0].cols;
816 int height = imgs[0].rows;
818 numPointSpectralChannels = numPointPanoramaCoords;
819 pointSpectralChannels =
ucharArr(
new unsigned char[numPointPanoramaCoords * n_channels]);
821 unsigned char* point_spectral_channels = pointSpectralChannels.get();
823 std::cout <<
timestamp <<
"Finished loading " << n_channels <<
" channel images" << std::endl;
825 #pragma omp parallel for 826 for (
int i = 0; i < numPointPanoramaCoords; i++)
828 int pc_index = 2 * i;
829 short x = point_panorama_coords[pc_index];
830 short y = point_panorama_coords[pc_index + 1];
831 x = (x + width / 2) % width;
833 int panoramaPosition = y * width + x;
834 unsigned char* pixel = point_spectral_channels + n_channels * i;
836 for (
int channel = 0; channel < n_channels; channel++)
838 pixel[channel] = pixels[channel][panoramaPosition];
841 std::cout <<
timestamp <<
"Finished extracting channel information" << std::endl;
852 pc->setPointArray(points, numPoints);
856 pc->setColorArray(pointColors, numPointColors);
859 if (pointIntensities)
861 pc->addFloatChannel(pointIntensities,
"intensities", numPointIntensities, 1);
864 if (pointConfidences)
866 pc->addFloatChannel(pointConfidences,
"confidences", numPointConfidence, 1);
871 pc->setNormalArray(pointNormals, numPointNormals);
875 if (pointSpectralChannels)
877 pc->addUCharChannel(pointSpectralChannels,
"spectral_channels", numPointSpectralChannels, n_channels);
880 pc->addIntAtomic(400,
"spectral_wavelength_min");
881 pc->addIntAtomic(400 + 4 * n_channels,
"spectral_wavelength_max");
882 pc->addIntAtomic(n_channels,
"num_spectral_channels");
889 mesh->setVertices(vertices, numVertices );
893 mesh->setFaceIndices(faceIndices, numFaces);
898 mesh->setVertexNormals(vertexNormals);
903 mesh->setVertexColors(vertexColors);
908 mesh->addFloatChannel(vertexIntensity,
"vertex_intensities", numVertexIntensities, 1);
911 if (vertexConfidence)
913 mesh->addFloatChannel(vertexConfidence,
"vertex_confidences", numVertexConfidences, 1);
950 unsigned int ** face;
951 long int length, value_index;
954 if ( value_index < 0 )
961 std::cerr <<
timestamp <<
"Mesh is not a triangle mesh." << std::endl;
A class to handle point information with an arbitrarily large number of attribute channels...
int ply_add_scalar_property(p_ply ply, const char *name, e_ply_type type)
void save(string filename)
Save PLY with previously specified data.
int ply_get_argument_user_data(p_ply_argument argument, void **pdata, long *idata)
std::shared_ptr< MeshBuffer > MeshBufferPtr
boost::shared_array< unsigned int > uintArr
double ply_get_argument_value(p_ply_argument argument)
boost::shared_array< short > shortArr
static Timestamp timestamp
A global time stamp object for program runtime measurement.
I/O support for PLY files.
ModelPtr read(string filename, bool readColor, bool readConfidence=true, bool readIntensity=true, bool readNormals=true, bool readFaces=true, bool readPanoramaCoords=true)
Read specified PLY file.
int ply_get_property_info(p_ply_property property, const char **name, e_ply_type *type, e_ply_type *length_type, e_ply_type *value_type)
boost::shared_array< unsigned char > ucharArr
int ply_write_header(p_ply ply)
enum e_ply_storage_mode_ e_ply_storage_mode
std::shared_ptr< PointBuffer > PointBufferPtr
p_ply_property ply_get_next_property(p_ply_element element, p_ply_property last)
p_ply ply_create(const char *name, e_ply_storage_mode storage_mode, p_ply_error_cb error_cb, long idata, void *pdata)
static int readColorCb(p_ply_argument argument)
Callback for read color information.
boost::shared_array< unsigned int > indexArray
long ply_set_read_cb(p_ply ply, const char *element_name, const char *property_name, p_ply_read_cb read_cb, void *pdata, long idata)
boost::shared_array< float > floatArr
int ply_add_element(p_ply ply, const char *name, long ninstances)
static int readPanoramaCoordCB(p_ply_argument argument)
Callback for read panorama coords.
static int readFaceCb(p_ply_argument argument)
Callback for read faces.
p_ply_element ply_get_next_element(p_ply ply, p_ply_element last)
int ply_get_argument_property(p_ply_argument argument, p_ply_property *property, long *length, long *value_index)
static int readVertexCb(p_ply_argument argument)
Callback for read vertices.
std::shared_ptr< Model > ModelPtr
int ply_get_element_info(p_ply_element element, const char **name, long *ninstances)
void swap(T *&arr, size_t i1, size_t i2, size_t n)
int ply_add_list_property(p_ply ply, const char *name, e_ply_type length_type, e_ply_type value_type)
p_ply ply_open(const char *name, p_ply_error_cb error_cb, long idata, void *pdata)
The MeshBuffer Mesh representation for I/O modules.
int ply_read_header(p_ply ply)
int ply_write(p_ply ply, double value)