Point Cloud Library (PCL) 1.15.1-dev
Loading...
Searching...
No Matches
ply_io.h
1/*
2 * Software License Agreement (BSD License)
3 *
4 * Point Cloud Library (PCL) - www.pointclouds.org
5 * Copyright (c) 2010-2011, Willow Garage, Inc.
6 *
7 * All rights reserved.
8 *
9 * Redistribution and use in source and binary forms, with or without
10 * modification, are permitted provided that the following conditions
11 * are met:
12 *
13 * * Redistributions of source code must retain the above copyright
14 * notice, this list of conditions and the following disclaimer.
15 * * Redistributions in binary form must reproduce the above
16 * copyright notice, this list of conditions and the following
17 * disclaimer in the documentation and/or other materials provided
18 * with the distribution.
19 * * Neither the name of the copyright holder(s) nor the names of its
20 * contributors may be used to endorse or promote products derived
21 * from this software without specific prior written permission.
22 *
23 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34 * POSSIBILITY OF SUCH DAMAGE.
35 *
36 * $Id$
37 *
38 */
39
40#pragma once
41
42#include <pcl/memory.h>
43#include <pcl/pcl_macros.h>
44#include <pcl/common/io.h> // for copyPointCloud
45#include <pcl/io/file_io.h>
46#include <pcl/io/ply/ply_parser.h>
47#include <pcl/PolygonMesh.h>
48
49#include <sstream>
50#include <tuple>
51
52namespace pcl
53{
54 /** \brief Point Cloud Data (PLY) file format reader.
55 *
56 * The PLY data format is organized in the following way:
57 * lines beginning with "comment" are treated as comments
58 * - ply
59 * - format [ascii|binary_little_endian|binary_big_endian] 1.0
60 * - element vertex COUNT
61 * - property float x
62 * - property float y
63 * - [property float z]
64 * - [property float normal_x]
65 * - [property float normal_y]
66 * - [property float normal_z]
67 * - [property uchar red]
68 * - [property uchar green]
69 * - [property uchar blue] ...
70 * - ascii/binary point coordinates
71 * - [element camera 1]
72 * - [property float view_px] ...
73 * - [element range_grid COUNT]
74 * - [property list uchar int vertex_indices]
75 * - end header
76 *
77 * \author Nizar Sallem
78 * \ingroup io
79 */
80 class PCL_EXPORTS PLYReader : public FileReader
81 {
82 public:
83 enum
84 {
85 PLY_V0 = 0,
86 PLY_V1 = 1
87 };
88
90 : origin_ (Eigen::Vector4f::Zero ())
91 , orientation_ (Eigen::Matrix3f::Identity ())
92 {}
93
95 : origin_ (Eigen::Vector4f::Zero ())
96 , orientation_ (Eigen::Matrix3f::Identity ())
97 {
98 *this = p;
99 }
100
101 PLYReader&
102 operator = (const PLYReader &p)
103 {
104 if (this == &p)
105 return *this;
106 origin_ = p.origin_;
107 orientation_ = p.orientation_;
108 range_grid_ = p.range_grid_;
109 polygons_ = p.polygons_;
110 return *this;
111 }
112
113 ~PLYReader () override { delete range_grid_; }
114 /** \brief Read a point cloud data header from a PLY file.
115 *
116 * Load only the meta information (number of points, their types, etc),
117 * and not the points themselves, from a given PLY file. Useful for fast
118 * evaluation of the underlying data structure.
119 *
120 * Returns:
121 * * < 0 (-1) on error
122 * * > 0 on success
123 * \param[in] file_name the name of the file to load
124 * \param[out] cloud the resultant point cloud dataset (only the header will be filled)
125 * \param[out] origin the sensor data acquisition origin (translation)
126 * \param[out] orientation the sensor data acquisition origin (rotation)
127 * \param[out] ply_version the PLY version read from the file
128 * \param[out] data_type the type of PLY data stored in the file
129 * \param[out] data_idx the data index
130 * \param[in] offset the offset in the file where to expect the true header to begin.
131 * One usage example for setting the offset parameter is for reading
132 * data from a TAR "archive containing multiple files: TAR files always
133 * add a 512 byte header in front of the actual file, so set the offset
134 * to the next byte after the header (e.g., 513).
135 */
136 int
137 readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
138 Eigen::Vector4f &origin, Eigen::Quaternionf &orientation,
139 int &ply_version, int &data_type, unsigned int &data_idx, const int offset = 0) override;
140
141 /** \brief Read a point cloud data from a PLY file and store it into a pcl/PCLPointCloud2.
142 * \param[in] file_name the name of the file containing the actual PointCloud data
143 * \param[out] cloud the resultant PointCloud message read from disk
144 * \param[out] origin the sensor data acquisition origin (translation)
145 * \param[out] orientation the sensor data acquisition origin (rotation)
146 * \param[out] ply_version the PLY version read from the file
147 * \param[in] offset the offset in the file where to expect the true header to begin.
148 * One usage example for setting the offset parameter is for reading
149 * data from a TAR "archive containing multiple files: TAR files always
150 * add a 512 byte header in front of the actual file, so set the offset
151 * to the next byte after the header (e.g., 513).
152 */
153 int
154 read (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
155 Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int& ply_version, const int offset = 0) override;
156
157 /** \brief Read a point cloud data from a PLY file and store it into a pcl/PCLPointCloud2.
158 * \note This function is provided for backwards compatibility only
159 * \param[in] file_name the name of the file containing the actual PointCloud data
160 * \param[out] cloud the resultant PointCloud message read from disk
161 * \param[in] offset the offset in the file where to expect the true header to begin.
162 * One usage example for setting the offset parameter is for reading
163 * data from a TAR "archive containing multiple files: TAR files always
164 * add a 512 byte header in front of the actual file, so set the offset
165 * to the next byte after the header (e.g., 513).
166 */
167 inline int
168 read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, const int offset = 0)
169 {
170 Eigen::Vector4f origin;
171 Eigen::Quaternionf orientation;
172 int ply_version;
173 return read (file_name, cloud, origin, orientation, ply_version, offset);
174 }
175
176 /** \brief Read a point cloud data from any PLY file, and convert it to the given template format.
177 * \param[in] file_name the name of the file containing the actual PointCloud data
178 * \param[out] cloud the resultant PointCloud message read from disk
179 * \param[in] offset the offset in the file where to expect the true header to begin.
180 * One usage example for setting the offset parameter is for reading
181 * data from a TAR "archive containing multiple files: TAR files always
182 * add a 512 byte header in front of the actual file, so set the offset
183 * to the next byte after the header (e.g., 513).
184 */
185 template<typename PointT> inline int
186 read (const std::string &file_name, pcl::PointCloud<PointT> &cloud, const int offset = 0)
187 {
189 int ply_version;
190 int res = read (file_name, blob, cloud.sensor_origin_, cloud.sensor_orientation_,
191 ply_version, offset);
192
193 // Exit in case of error
194 if (res < 0)
195 return (res);
196 pcl::fromPCLPointCloud2 (blob, cloud);
197 return (0);
198 }
199
200 /** \brief Read a point cloud data from a PLY file and store it into a pcl/PolygonMesh.
201 *
202 * \param[in] file_name the name of the file containing the actual PointCloud data
203 * \param[out] mesh the resultant PolygonMesh message read from disk
204 * \param[out] origin the sensor data acquisition origin (translation)
205 * \param[out] orientation the sensor data acquisition origin (rotation)
206 * \param[out] ply_version the PLY version read from the file
207 * \param[in] offset the offset in the file where to expect the true header to begin.
208 * One usage example for setting the offset parameter is for reading
209 * data from a TAR "archive containing multiple files: TAR files always
210 * add a 512 byte header in front of the actual file, so set the offset
211 * to the next byte after the header (e.g., 513).
212 */
213 int
214 read (const std::string &file_name, pcl::PolygonMesh &mesh,
215 Eigen::Vector4f &origin, Eigen::Quaternionf &orientation,
216 int& ply_version, const int offset = 0);
217
218 /** \brief Read a point cloud data from a PLY file and store it into a pcl/PolygonMesh.
219 *
220 * \param[in] file_name the name of the file containing the actual PointCloud data
221 * \param[out] mesh the resultant PolygonMesh message read from disk
222 * \param[in] offset the offset in the file where to expect the true header to begin.
223 * One usage example for setting the offset parameter is for reading
224 * data from a TAR "archive containing multiple files: TAR files always
225 * add a 512 byte header in front of the actual file, so set the offset
226 * to the next byte after the header (e.g., 513).
227 */
228 int
229 read (const std::string &file_name, pcl::PolygonMesh &mesh, const int offset = 0);
230
231 private:
233
234 bool
235 parse (const std::string& istream_filename);
236
237 /** \brief Info callback function
238 * \param[in] filename PLY file read
239 * \param[in] line_number line triggering the callback
240 * \param[in] message information message
241 */
242 void
243 infoCallback (const std::string& filename, std::size_t line_number, const std::string& message)
244 {
245 PCL_DEBUG ("[pcl::PLYReader] %s:%lu: %s\n", filename.c_str (), line_number, message.c_str ());
246 }
247
248 /** \brief Warning callback function
249 * \param[in] filename PLY file read
250 * \param[in] line_number line triggering the callback
251 * \param[in] message warning message
252 */
253 void
254 warningCallback (const std::string& filename, std::size_t line_number, const std::string& message)
255 {
256 PCL_WARN ("[pcl::PLYReader] %s:%lu: %s\n", filename.c_str (), line_number, message.c_str ());
257 }
258
259 /** \brief Error callback function
260 * \param[in] filename PLY file read
261 * \param[in] line_number line triggering the callback
262 * \param[in] message error message
263 */
264 void
265 errorCallback (const std::string& filename, std::size_t line_number, const std::string& message)
266 {
267 PCL_ERROR ("[pcl::PLYReader] %s:%lu: %s\n", filename.c_str (), line_number, message.c_str ());
268 }
269
270 /** \brief function called when the keyword element is parsed
271 * \param[in] element_name element name
272 * \param[in] count number of instances
273 */
274 std::tuple<std::function<void ()>, std::function<void ()> >
275 elementDefinitionCallback (const std::string& element_name, std::size_t count);
276
277 bool
278 endHeaderCallback ();
279
280 /** \brief function called when a scalar property is parsed
281 * \param[in] element_name element name to which the property belongs
282 * \param[in] property_name property name
283 */
284 template <typename ScalarType> std::function<void (ScalarType)>
285 scalarPropertyDefinitionCallback (const std::string& element_name, const std::string& property_name);
286
287 /** \brief function called when a list property is parsed
288 * \param[in] element_name element name to which the property belongs
289 * \param[in] property_name list property name
290 */
291 template <typename SizeType, typename ScalarType>
292 std::tuple<std::function<void (SizeType)>, std::function<void (ScalarType)>, std::function<void ()> >
293 listPropertyDefinitionCallback (const std::string& element_name, const std::string& property_name);
294
295 /** \brief function called at the beginning of a list property parsing.
296 * \param[in] size number of elements in the list
297 */
298 template <typename SizeType> void
299 vertexListPropertyBeginCallback (const std::string& property_name, SizeType size);
300
301 /** \brief function called when a list element is parsed.
302 * \param[in] value the list's element value
303 */
304 template <typename ContentType> void
305 vertexListPropertyContentCallback (ContentType value);
306
307 /** \brief function called at the end of a list property parsing */
308 inline void
309 vertexListPropertyEndCallback ();
310
311 /** Callback function for an anonymous vertex scalar property.
312 * Writes down a double value in cloud data.
313 * param[in] value double value parsed
314 */
315 template<typename Scalar> void
316 vertexScalarPropertyCallback (Scalar value);
317
318 /** Callback function for vertex RGB color.
319 * This callback is in charge of packing red green and blue in a single int
320 * before writing it down in cloud data.
321 * param[in] color_name color name in {red, green, blue}
322 * param[in] color value of {red, green, blue} property
323 */
324 inline void
325 vertexColorCallback (const std::string& color_name, pcl::io::ply::uint8 color);
326
327 /** Callback function for vertex intensity.
328 * converts intensity from int to float before writing it down in cloud data.
329 * param[in] intensity
330 */
331 inline void
332 vertexIntensityCallback (pcl::io::ply::uint8 intensity);
333
334 /** Callback function for vertex alpha.
335 * extracts RGB value, append alpha and put it back
336 * param[in] alpha
337 */
338 inline void
339 vertexAlphaCallback (pcl::io::ply::uint8 alpha);
340
341 /** Callback function for origin x component.
342 * param[in] value origin x value
343 */
344 inline void
345 originXCallback (const float& value) { origin_[0] = value; }
346
347 /** Callback function for origin y component.
348 * param[in] value origin y value
349 */
350 inline void
351 originYCallback (const float& value) { origin_[1] = value; }
352
353 /** Callback function for origin z component.
354 * param[in] value origin z value
355 */
356 inline void
357 originZCallback (const float& value) { origin_[2] = value; }
358
359 /** Callback function for orientation x axis x component.
360 * param[in] value orientation x axis x value
361 */
362 inline void
363 orientationXaxisXCallback (const float& value) { orientation_ (0,0) = value; }
364
365 /** Callback function for orientation x axis y component.
366 * param[in] value orientation x axis y value
367 */
368 inline void
369 orientationXaxisYCallback (const float& value) { orientation_ (0,1) = value; }
370
371 /** Callback function for orientation x axis z component.
372 * param[in] value orientation x axis z value
373 */
374 inline void
375 orientationXaxisZCallback (const float& value) { orientation_ (0,2) = value; }
376
377 /** Callback function for orientation y axis x component.
378 * param[in] value orientation y axis x value
379 */
380 inline void
381 orientationYaxisXCallback (const float& value) { orientation_ (1,0) = value; }
382
383 /** Callback function for orientation y axis y component.
384 * param[in] value orientation y axis y value
385 */
386 inline void
387 orientationYaxisYCallback (const float& value) { orientation_ (1,1) = value; }
388
389 /** Callback function for orientation y axis z component.
390 * param[in] value orientation y axis z value
391 */
392 inline void
393 orientationYaxisZCallback (const float& value) { orientation_ (1,2) = value; }
394
395 /** Callback function for orientation z axis x component.
396 * param[in] value orientation z axis x value
397 */
398 inline void
399 orientationZaxisXCallback (const float& value) { orientation_ (2,0) = value; }
400
401 /** Callback function for orientation z axis y component.
402 * param[in] value orientation z axis y value
403 */
404 inline void
405 orientationZaxisYCallback (const float& value) { orientation_ (2,1) = value; }
406
407 /** Callback function for orientation z axis z component.
408 * param[in] value orientation z axis z value
409 */
410 inline void
411 orientationZaxisZCallback (const float& value) { orientation_ (2,2) = value; }
412
413 /** Callback function to set the cloud height
414 * param[in] height cloud height
415 */
416 inline void
417 cloudHeightCallback (const int &height) { cloud_->height = height; }
418
419 /** Callback function to set the cloud width
420 * param[in] width cloud width
421 */
422 inline void
423 cloudWidthCallback (const int &width) { cloud_->width = width; }
424
425 /** Append a scalar property to the cloud fields.
426 * param[in] name property name
427 * param[in] count property count: 1 for scalar properties and higher for a
428 * list property.
429 */
430 template<typename Scalar> void
431 appendScalarProperty (const std::string& name, const std::size_t& count = 1);
432
433 /** Amend property from cloud fields identified by \a old_name renaming
434 * it \a new_name.
435 * * Returns:
436 * * false on error
437 * * true success
438 * param[in] old_name property old name
439 * param[in] new_name property new name
440 */
441 bool
442 amendProperty (const std::string& old_name, const std::string& new_name, std::uint8_t datatype = 0);
443
444 /** Callback function for the begin of vertex line */
445 void
446 vertexBeginCallback ();
447
448 /** Callback function for the end of vertex line */
449 void
450 vertexEndCallback ();
451
452 /** Callback function for the begin of range_grid line */
453 void
454 rangeGridBeginCallback ();
455
456 /** Callback function for the begin of range_grid vertex_indices property
457 * param[in] size vertex_indices list size
458 */
459 void
460 rangeGridVertexIndicesBeginCallback (pcl::io::ply::uint8 size);
461
462 /** Callback function for each range_grid vertex_indices element
463 * param[in] vertex_index index of the vertex in vertex_indices
464 */
465 void
466 rangeGridVertexIndicesElementCallback (pcl::io::ply::int32 vertex_index);
467
468 /** Callback function for the end of a range_grid vertex_indices property */
469 void
470 rangeGridVertexIndicesEndCallback ();
471
472 /** Callback function for the end of a range_grid element end */
473 void
474 rangeGridEndCallback ();
475
476 /** Callback function for obj_info */
477 void
478 objInfoCallback (const std::string& line);
479
480 /** Callback function for the begin of face line */
481 void
482 faceBeginCallback ();
483
484 /** Callback function for the begin of face vertex_indices property
485 * param[in] size vertex_indices list size
486 */
487 void
488 faceVertexIndicesBeginCallback (pcl::io::ply::uint8 size);
489
490 /** Callback function for each face vertex_indices element
491 * param[in] vertex_index index of the vertex in vertex_indices
492 */
493 void
494 faceVertexIndicesElementCallback (pcl::io::ply::int32 vertex_index);
495
496 /** Callback function for the end of a face vertex_indices property */
497 void
498 faceVertexIndicesEndCallback ();
499
500 /** Callback function for the end of a face element end */
501 void
502 faceEndCallback ();
503
504 /// origin
505 Eigen::Vector4f origin_;
506
507 /// orientation
508 Eigen::Matrix3f orientation_;
509
510 //vertex element artifacts
511 pcl::PCLPointCloud2 *cloud_{nullptr};
512 std::size_t vertex_count_{0};
513 int vertex_offset_before_{0};
514 //range element artifacts
515 std::vector<std::vector <int> > *range_grid_{nullptr};
516 std::size_t rgb_offset_before_{0};
517 bool do_resize_{false};
518 //face element artifact
519 std::vector<pcl::Vertices> *polygons_{nullptr};
520 public:
522
523 private:
524 // RGB values stored by vertexColorCallback()
525 std::int32_t r_{0}, g_{0}, b_{0};
526 // Color values stored by vertexAlphaCallback()
527 std::uint32_t a_{0}, rgba_{0};
528 };
529
530 /** \brief Point Cloud Data (PLY) file format writer.
531 * \author Nizar Sallem
532 * \ingroup io
533 */
534 class PCL_EXPORTS PLYWriter : public FileWriter
535 {
536 public:
537 ///Constructor
538 PLYWriter () = default;
539
540 ///Destructor
541 ~PLYWriter () override = default;
542
543 /** \brief Generate the header of a PLY v.7 file format
544 * \param[in] cloud the point cloud data message
545 * \param[in] origin the sensor data acquisition origin (translation)
546 * \param[in] orientation the sensor data acquisition origin (rotation)
547 * \param[in] valid_points number of valid points (finite ones for range_grid and
548 * all of them for camer)
549 * \param[in] use_camera if set to true then PLY file will use element camera else
550 * element range_grid will be used.
551 */
552 inline std::string
554 const Eigen::Vector4f &origin,
555 const Eigen::Quaternionf &orientation,
556 int valid_points,
557 bool use_camera = true)
558 {
559 return (generateHeader (cloud, origin, orientation, true, use_camera, valid_points));
560 }
561
562 /** \brief Generate the header of a PLY v.7 file format
563 * \param[in] cloud the point cloud data message
564 * \param[in] origin the sensor data acquisition origin (translation)
565 * \param[in] orientation the sensor data acquisition origin (rotation)
566 * \param[in] valid_points number of valid points (finite ones for range_grid and
567 * all of them for camer)
568 * \param[in] use_camera if set to true then PLY file will use element camera else
569 * element range_grid will be used.
570 */
571 inline std::string
573 const Eigen::Vector4f &origin,
574 const Eigen::Quaternionf &orientation,
575 int valid_points,
576 bool use_camera = true)
577 {
578 return (generateHeader (cloud, origin, orientation, false, use_camera, valid_points));
579 }
580
581 /** \brief Save point cloud data to a PLY file containing n-D points, in ASCII format
582 * \param[in] file_name the output file name
583 * \param[in] cloud the point cloud data message
584 * \param[in] origin the sensor data acquisition origin (translation)
585 * \param[in] orientation the sensor data acquisition origin (rotation)
586 * \param[in] precision the specified output numeric stream precision (default: 8)
587 * \param[in] use_camera if set to true then PLY file will use element camera else
588 * element range_grid will be used.
589 */
590 int
591 writeASCII (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
592 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
593 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
594 int precision = 8,
595 bool use_camera = true);
596 /** \brief Save point cloud data to a std::ostream containing n-D points, in BINARY format
597 * \param[in] os the output buffer
598 * \param[in] cloud the point cloud data message
599 * \param[in] origin the sensor data acquisition origin
600 * (translation) \param[in] orientation the sensor data acquisition origin
601 * (rotation) \param[in] use_camera if set to true then PLY file will use element
602 * camera else element range_grid will be used
603 */
604 int
605 writeBinary(std::ostream& os, const pcl::PCLPointCloud2& cloud,
606 const Eigen::Vector4f& origin = Eigen::Vector4f::Zero (), const Eigen::Quaternionf& orientation= Eigen::Quaternionf::Identity (),
607 bool use_camera=true);
608
609 /** \brief Save point cloud data to a PLY file containing n-D points, in BINARY format
610 * \param[in] file_name the output file name
611 * \param[in] cloud the point cloud data message
612 * \param[in] origin the sensor data acquisition origin (translation)
613 * \param[in] orientation the sensor data acquisition origin (rotation)
614 * \param[in] use_camera if set to true then PLY file will use element camera else
615 * element range_grid will be used
616 */
617 int
618 writeBinary (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
619 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
620 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
621 bool use_camera = true);
622
623 /** \brief Save point cloud data to a PLY file containing n-D points
624 * \param[in] file_name the output file name
625 * \param[in] cloud the point cloud data message
626 * \param[in] origin the sensor acquisition origin
627 * \param[in] orientation the sensor acquisition orientation
628 * \param[in] binary set to true if the file is to be written in a binary
629 * PLY format, false (default) for ASCII
630 */
631 inline int
632 write (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
633 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
634 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
635 const bool binary = false) override
636 {
637 if (binary)
638 return (this->writeBinary (file_name, cloud, origin, orientation, true));
639 return (this->writeASCII (file_name, cloud, origin, orientation, 8, true));
640 }
641
642 /** \brief Save point cloud data to a PLY file containing n-D points
643 * \param[in] file_name the output file name
644 * \param[in] cloud the point cloud data message
645 * \param[in] origin the sensor acquisition origin
646 * \param[in] orientation the sensor acquisition orientation
647 * \param[in] binary set to true if the file is to be written in a binary
648 * PLY format, false (default) for ASCII
649 * \param[in] use_camera set to true to use camera element and false to
650 * use range_grid element
651 */
652 inline int
653 write (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
654 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
655 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
656 bool binary = false,
657 bool use_camera = true)
658 {
659 if (binary)
660 return (this->writeBinary (file_name, cloud, origin, orientation, use_camera));
661 return (this->writeASCII (file_name, cloud, origin, orientation, 8, use_camera));
662 }
663
664 /** \brief Save point cloud data to a PLY file containing n-D points
665 * \param[in] file_name the output file name
666 * \param[in] cloud the point cloud data message (boost shared pointer)
667 * \param[in] origin the sensor acquisition origin
668 * \param[in] orientation the sensor acquisition orientation
669 * \param[in] binary set to true if the file is to be written in a binary
670 * PLY format, false (default) for ASCII
671 * \param[in] use_camera set to true to use camera element and false to
672 * use range_grid element
673 */
674 inline int
675 write (const std::string &file_name, const pcl::PCLPointCloud2::ConstPtr &cloud,
676 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
677 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
678 bool binary = false,
679 bool use_camera = true)
680 {
681 return (write (file_name, *cloud, origin, orientation, binary, use_camera));
682 }
683
684 /** \brief Save point cloud data to a PLY file containing n-D points
685 * \param[in] file_name the output file name
686 * \param[in] cloud the pcl::PointCloud data
687 * \param[in] binary set to true if the file is to be written in a binary
688 * PLY format, false (default) for ASCII
689 * \param[in] use_camera set to true to use camera element and false to
690 * use range_grid element
691 */
692 template<typename PointT> inline int
693 write (const std::string &file_name,
694 const pcl::PointCloud<PointT> &cloud,
695 bool binary = false,
696 bool use_camera = true)
697 {
698 Eigen::Vector4f origin = cloud.sensor_origin_;
699 Eigen::Quaternionf orientation = cloud.sensor_orientation_;
700
702 pcl::toPCLPointCloud2 (cloud, blob);
703
704 // Save the data
705 return (this->write (file_name, blob, origin, orientation, binary, use_camera));
706 }
707
708 private:
709 /** \brief Generate a PLY header.
710 * \param[in] cloud the input point cloud
711 * \param[in] binary whether the PLY file should be saved as binary data (true) or ascii (false)
712 */
713 std::string
714 generateHeader (const pcl::PCLPointCloud2 &cloud,
715 const Eigen::Vector4f &origin,
716 const Eigen::Quaternionf &orientation,
717 bool binary,
718 bool use_camera,
719 int valid_points);
720
721 void
722 writeContentWithCameraASCII (int nr_points,
723 const pcl::PCLPointCloud2 &cloud,
724 const Eigen::Vector4f &origin,
725 const Eigen::Quaternionf &orientation,
726 std::ofstream& fs);
727
728 void
729 writeContentWithRangeGridASCII (int nr_points,
730 const pcl::PCLPointCloud2 &cloud,
731 std::ostringstream& fs,
732 int& nb_valid_points);
733 };
734
735 namespace io
736 {
737 /** \brief Load a PLY v.6 file into a PCLPointCloud2 type.
738 *
739 * Any PLY files containing sensor data will generate a warning as a
740 * pcl/PCLPointCloud2 message cannot hold the sensor origin.
741 *
742 * \param[in] file_name the name of the file to load
743 * \param[in] cloud the resultant templated point cloud
744 * \ingroup io
745 */
746 inline int
747 loadPLYFile (const std::string &file_name, pcl::PCLPointCloud2 &cloud)
748 {
750 return (p.read (file_name, cloud));
751 }
752
753 /** \brief Load any PLY file into a PCLPointCloud2 type.
754 * \param[in] file_name the name of the file to load
755 * \param[out] cloud the resultant templated point cloud
756 * \param[out] origin the sensor acquisition origin (only for > PLY_V7 - null if not present)
757 * \param[out] orientation the sensor acquisition orientation if available,
758 * identity if not present
759 * \ingroup io
760 */
761 inline int
762 loadPLYFile (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
763 Eigen::Vector4f &origin, Eigen::Quaternionf &orientation)
764 {
766 int ply_version;
767 return (p.read (file_name, cloud, origin, orientation, ply_version));
768 }
769
770 /** \brief Load any PLY file into a templated PointCloud type
771 * \param[in] file_name the name of the file to load
772 * \param[in] cloud the resultant templated point cloud
773 * \ingroup io
774 */
775 template<typename PointT> inline int
776 loadPLYFile (const std::string &file_name, pcl::PointCloud<PointT> &cloud)
777 {
779 return (p.read (file_name, cloud));
780 }
781
782 /** \brief Load a PLY file into a PolygonMesh type.
783 *
784 * Any PLY files containing sensor data will generate a warning as a
785 * pcl/PolygonMesh message cannot hold the sensor origin.
786 *
787 * \param[in] file_name the name of the file to load
788 * \param[in] mesh the resultant polygon mesh
789 * \ingroup io
790 */
791 inline int
792 loadPLYFile (const std::string &file_name, pcl::PolygonMesh &mesh)
793 {
795 return (p.read (file_name, mesh));
796 }
797
798 /** \brief Save point cloud data to a PLY file containing n-D points
799 * \param[in] file_name the output file name
800 * \param[in] cloud the point cloud data message
801 * \param[in] origin the sensor data acquisition origin (translation)
802 * \param[in] orientation the sensor data acquisition origin (rotation)
803 * \param[in] binary_mode true for binary mode, false (default) for ASCII
804 * \param[in] use_camera
805 * \ingroup io
806 */
807 inline int
808 savePLYFile (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
809 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
810 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
811 bool binary_mode = false, bool use_camera = true)
812 {
813 PLYWriter w;
814 return (w.write (file_name, cloud, origin, orientation, binary_mode, use_camera));
815 }
816
817 /** \brief Templated version for saving point cloud data to a PLY file
818 * containing a specific given cloud format
819 * \param[in] file_name the output file name
820 * \param[in] cloud the point cloud data message
821 * \param[in] binary_mode true for binary mode, false (default) for ASCII
822 * \ingroup io
823 */
824 template<typename PointT> inline int
825 savePLYFile (const std::string &file_name, const pcl::PointCloud<PointT> &cloud, bool binary_mode = false)
826 {
827 PLYWriter w;
828 return (w.write<PointT> (file_name, cloud, binary_mode));
829 }
830
831 /** \brief Templated version for saving point cloud data to a PLY file
832 * containing a specific given cloud format.
833 * \param[in] file_name the output file name
834 * \param[in] cloud the point cloud data message
835 * \ingroup io
836 */
837 template<typename PointT> inline int
838 savePLYFileASCII (const std::string &file_name, const pcl::PointCloud<PointT> &cloud)
839 {
840 PLYWriter w;
841 return (w.write<PointT> (file_name, cloud, false));
842 }
843
844 /** \brief Templated version for saving point cloud data to a PLY file containing a specific given cloud format.
845 * \param[in] file_name the output file name
846 * \param[in] cloud the point cloud data message
847 * \ingroup io
848 */
849 template<typename PointT> inline int
850 savePLYFileBinary (const std::string &file_name, const pcl::PointCloud<PointT> &cloud)
851 {
852 PLYWriter w;
853 return (w.write<PointT> (file_name, cloud, true));
854 }
855
856 /** \brief Templated version for saving point cloud data to a PLY file containing a specific given cloud format
857 * \param[in] file_name the output file name
858 * \param[in] cloud the point cloud data message
859 * \param[in] indices the set of indices to save
860 * \param[in] binary_mode true for binary mode, false (default) for ASCII
861 * \ingroup io
862 */
863 template<typename PointT> int
864 savePLYFile (const std::string &file_name, const pcl::PointCloud<PointT> &cloud,
865 const pcl::Indices &indices, bool binary_mode = false)
866 {
867 // Copy indices to a new point cloud
868 pcl::PointCloud<PointT> cloud_out;
869 copyPointCloud (cloud, indices, cloud_out);
870 // Save the data
871 PLYWriter w;
872 return (w.write<PointT> (file_name, cloud_out, binary_mode));
873 }
874
875 /** \brief Saves a PolygonMesh in ascii PLY format.
876 * \param[in] file_name the name of the file to write to disk
877 * \param[in] mesh the polygonal mesh to save
878 * \param[in] precision the output ASCII precision default 5
879 * \ingroup io
880 */
881 PCL_EXPORTS int
882 savePLYFile (const std::string &file_name, const pcl::PolygonMesh &mesh, unsigned precision = 5);
883
884 /** \brief Saves a PolygonMesh in binary PLY format.
885 * \param[in] file_name the name of the file to write to disk
886 * \param[in] mesh the polygonal mesh to save
887 * \ingroup io
888 */
889 PCL_EXPORTS int
890 savePLYFileBinary (const std::string &file_name, const pcl::PolygonMesh &mesh);
891 }
892}
Point Cloud Data (FILE) file format reader interface.
Definition file_io.h:57
Point Cloud Data (FILE) file format writer.
Definition file_io.h:163
Point Cloud Data (PLY) file format reader.
Definition ply_io.h:81
int read(const std::string &file_name, pcl::PCLPointCloud2 &cloud, const int offset=0)
Read a point cloud data from a PLY file and store it into a pcl/PCLPointCloud2.
Definition ply_io.h:168
int read(const std::string &file_name, pcl::PointCloud< PointT > &cloud, const int offset=0)
Read a point cloud data from any PLY file, and convert it to the given template format.
Definition ply_io.h:186
int read(const std::string &file_name, pcl::PolygonMesh &mesh, const int offset=0)
Read a point cloud data from a PLY file and store it into a pcl/PolygonMesh.
~PLYReader() override
Definition ply_io.h:113
int read(const std::string &file_name, pcl::PCLPointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &ply_version, const int offset=0) override
Read a point cloud data from a PLY file and store it into a pcl/PCLPointCloud2.
PLYReader(const PLYReader &p)
Definition ply_io.h:94
int readHeader(const std::string &file_name, pcl::PCLPointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &ply_version, int &data_type, unsigned int &data_idx, const int offset=0) override
Read a point cloud data header from a PLY file.
int read(const std::string &file_name, pcl::PolygonMesh &mesh, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &ply_version, const int offset=0)
Read a point cloud data from a PLY file and store it into a pcl/PolygonMesh.
Point Cloud Data (PLY) file format writer.
Definition ply_io.h:535
std::string generateHeaderBinary(const pcl::PCLPointCloud2 &cloud, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation, int valid_points, bool use_camera=true)
Generate the header of a PLY v.7 file format.
Definition ply_io.h:553
int write(const std::string &file_name, const pcl::PCLPointCloud2 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), bool binary=false, bool use_camera=true)
Save point cloud data to a PLY file containing n-D points.
Definition ply_io.h:653
int writeBinary(const std::string &file_name, const pcl::PCLPointCloud2 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), bool use_camera=true)
Save point cloud data to a PLY file containing n-D points, in BINARY format.
~PLYWriter() override=default
Destructor.
int write(const std::string &file_name, const pcl::PCLPointCloud2 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), const bool binary=false) override
Save point cloud data to a PLY file containing n-D points.
Definition ply_io.h:632
int write(const std::string &file_name, const pcl::PointCloud< PointT > &cloud, bool binary=false, bool use_camera=true)
Save point cloud data to a PLY file containing n-D points.
Definition ply_io.h:693
int writeBinary(std::ostream &os, const pcl::PCLPointCloud2 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), bool use_camera=true)
Save point cloud data to a std::ostream containing n-D points, in BINARY format.
int write(const std::string &file_name, const pcl::PCLPointCloud2::ConstPtr &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), bool binary=false, bool use_camera=true)
Save point cloud data to a PLY file containing n-D points.
Definition ply_io.h:675
std::string generateHeaderASCII(const pcl::PCLPointCloud2 &cloud, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation, int valid_points, bool use_camera=true)
Generate the header of a PLY v.7 file format.
Definition ply_io.h:572
int writeASCII(const std::string &file_name, const pcl::PCLPointCloud2 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), int precision=8, bool use_camera=true)
Save point cloud data to a PLY file containing n-D points, in ASCII format.
PLYWriter()=default
Constructor.
PointCloud represents the base class in PCL for storing collections of 3D points.
Eigen::Quaternionf sensor_orientation_
Sensor acquisition pose (rotation).
Eigen::Vector4f sensor_origin_
Sensor acquisition pose (origin/translation).
Class ply_parser parses a PLY file and generates appropriate atomic parsers for the body.
Definition ply_parser.h:74
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition memory.h:86
void copyPointCloud(const pcl::PointCloud< PointInT > &cloud_in, pcl::PointCloud< PointOutT > &cloud_out)
Copy all the fields from a given point cloud into a new point cloud.
Definition io.hpp:208
Defines functions, macros and traits for allocating and using memory.
Definition bfgs.h:12
std::int32_t int32
Definition ply.h:60
std::uint8_t uint8
Definition ply.h:61
void read(std::istream &stream, Type &value)
Function for reading data from a stream.
Definition region_xy.h:46
void fromPCLPointCloud2(const pcl::PCLPointCloud2 &msg, pcl::PointCloud< PointT > &cloud, const MsgFieldMap &field_map, const std::uint8_t *msg_data)
Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
void toPCLPointCloud2(const pcl::PointCloud< PointT > &cloud, pcl::PCLPointCloud2 &msg, bool padding)
Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition types.h:133
void write(std::ostream &stream, Type value)
Function for writing data to a stream.
Definition region_xy.h:63
Defines all the PCL and non-PCL macros used.
shared_ptr< const ::pcl::PCLPointCloud2 > ConstPtr
A point structure representing Euclidean xyz coordinates, and the RGB color.