00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #ifndef PCL_IO_PLY_IO_H_
00041 #define PCL_IO_PLY_IO_H_
00042
00043 #include <pcl/io/boost.h>
00044 #include <pcl/io/file_io.h>
00045 #include <pcl/io/ply/ply_parser.h>
00046 #include <pcl/PolygonMesh.h>
00047 #include <sstream>
00048
00049 namespace pcl
00050 {
00077 class PCL_EXPORTS PLYReader : public FileReader
00078 {
00079 public:
00080 enum
00081 {
00082 PLY_V0 = 0,
00083 PLY_V1 = 1
00084 };
00085
00086 PLYReader ()
00087 : FileReader ()
00088 , parser_ ()
00089 , origin_ (Eigen::Vector4f::Zero ())
00090 , orientation_ (Eigen::Matrix3f::Zero ())
00091 , cloud_ ()
00092 , vertex_count_ (0)
00093 , vertex_properties_counter_ (0)
00094 , vertex_offset_before_ (0)
00095 , range_grid_ (0)
00096 , range_count_ (0)
00097 , range_grid_vertex_indices_element_index_ (0)
00098 , rgb_offset_before_ (0)
00099 , do_resize_ (false)
00100 {}
00101
00102 PLYReader (const PLYReader &p)
00103 : FileReader ()
00104 , parser_ ()
00105 , origin_ (Eigen::Vector4f::Zero ())
00106 , orientation_ (Eigen::Matrix3f::Zero ())
00107 , cloud_ ()
00108 , vertex_count_ (0)
00109 , vertex_properties_counter_ (0)
00110 , vertex_offset_before_ (0)
00111 , range_grid_ (0)
00112 , range_count_ (0)
00113 , range_grid_vertex_indices_element_index_ (0)
00114 , rgb_offset_before_ (0)
00115 , do_resize_ (false)
00116 {
00117 *this = p;
00118 }
00119
00120 PLYReader&
00121 operator = (const PLYReader &p)
00122 {
00123 origin_ = p.origin_;
00124 orientation_ = p.orientation_;
00125 range_grid_ = p.range_grid_;
00126 return (*this);
00127 }
00128
00129 ~PLYReader () { delete range_grid_; }
00152 int
00153 readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
00154 Eigen::Vector4f &origin, Eigen::Quaternionf &orientation,
00155 int &ply_version, int &data_type, unsigned int &data_idx, const int offset = 0);
00156
00169 int
00170 read (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
00171 Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int& ply_version, const int offset = 0);
00172
00188 inline int
00189 read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, const int offset = 0)
00190 {
00191 Eigen::Vector4f origin;
00192 Eigen::Quaternionf orientation;
00193 int ply_version;
00194 return read (file_name, cloud, origin, orientation, ply_version, offset);
00195 }
00196
00206 template<typename PointT> inline int
00207 read (const std::string &file_name, pcl::PointCloud<PointT> &cloud, const int offset = 0)
00208 {
00209 pcl::PCLPointCloud2 blob;
00210 int ply_version;
00211 int res = read (file_name, blob, cloud.sensor_origin_, cloud.sensor_orientation_,
00212 ply_version, offset);
00213
00214
00215 if (res < 0)
00216 return (res);
00217 pcl::fromPCLPointCloud2 (blob, cloud);
00218 return (0);
00219 }
00220
00221 private:
00222 ::pcl::io::ply::ply_parser parser_;
00223
00224 bool
00225 parse (const std::string& istream_filename);
00226
00232 void
00233 infoCallback (const std::string& filename, std::size_t line_number, const std::string& message)
00234 {
00235 PCL_DEBUG ("[pcl::PLYReader] %s:%lu: %s\n", filename.c_str (), line_number, message.c_str ());
00236 }
00237
00243 void
00244 warningCallback (const std::string& filename, std::size_t line_number, const std::string& message)
00245 {
00246 PCL_WARN ("[pcl::PLYReader] %s:%lu: %s\n", filename.c_str (), line_number, message.c_str ());
00247 }
00248
00254 void
00255 errorCallback (const std::string& filename, std::size_t line_number, const std::string& message)
00256 {
00257 PCL_ERROR ("[pcl::PLYReader] %s:%lu: %s\n", filename.c_str (), line_number, message.c_str ());
00258 }
00259
00264 boost::tuple<boost::function<void ()>, boost::function<void ()> >
00265 elementDefinitionCallback (const std::string& element_name, std::size_t count);
00266
00267 bool
00268 endHeaderCallback ();
00269
00274 template <typename ScalarType> boost::function<void (ScalarType)>
00275 scalarPropertyDefinitionCallback (const std::string& element_name, const std::string& property_name);
00276
00281 template <typename SizeType, typename ScalarType>
00282 boost::tuple<boost::function<void (SizeType)>, boost::function<void (ScalarType)>, boost::function<void ()> >
00283 listPropertyDefinitionCallback (const std::string& element_name, const std::string& property_name);
00284
00288 template <typename SizeType> void
00289 vertexListPropertyBeginCallback (const std::string& property_name, SizeType size);
00290
00294 template <typename ContentType> void
00295 vertexListPropertyContentCallback (ContentType value);
00296
00298 inline void
00299 vertexListPropertyEndCallback ();
00300
00305 inline void
00306 vertexDoublePropertyCallback (pcl::io::ply::float64 value);
00307
00312 inline void
00313 vertexFloatPropertyCallback (pcl::io::ply::float32 value);
00314
00319 inline void
00320 vertexIntPropertyCallback (pcl::io::ply::int32 value);
00321
00326 inline void
00327 vertexUnsignedIntPropertyCallback (pcl::io::ply::uint32 value);
00328
00333 inline void
00334 vertexShortPropertyCallback (pcl::io::ply::int16 value);
00335
00340 inline void
00341 vertexUnsignedShortPropertyCallback (pcl::io::ply::uint16 value);
00342
00347 inline void
00348 vertexCharPropertyCallback (pcl::io::ply::int8 value);
00349
00354 inline void
00355 vertexUnsignedCharPropertyCallback (pcl::io::ply::uint8 value);
00356
00363 inline void
00364 vertexColorCallback (const std::string& color_name, pcl::io::ply::uint8 color);
00365
00370 inline void
00371 vertexIntensityCallback (pcl::io::ply::uint8 intensity);
00372
00377 inline void
00378 vertexAlphaCallback (pcl::io::ply::uint8 alpha);
00379
00383 inline void
00384 originXCallback (const float& value) { origin_[0] = value; }
00385
00389 inline void
00390 originYCallback (const float& value) { origin_[1] = value; }
00391
00395 inline void
00396 originZCallback (const float& value) { origin_[2] = value; }
00397
00401 inline void
00402 orientationXaxisXCallback (const float& value) { orientation_ (0,0) = value; }
00403
00407 inline void
00408 orientationXaxisYCallback (const float& value) { orientation_ (0,1) = value; }
00409
00413 inline void
00414 orientationXaxisZCallback (const float& value) { orientation_ (0,2) = value; }
00415
00419 inline void
00420 orientationYaxisXCallback (const float& value) { orientation_ (1,0) = value; }
00421
00425 inline void
00426 orientationYaxisYCallback (const float& value) { orientation_ (1,1) = value; }
00427
00431 inline void
00432 orientationYaxisZCallback (const float& value) { orientation_ (1,2) = value; }
00433
00437 inline void
00438 orientationZaxisXCallback (const float& value) { orientation_ (2,0) = value; }
00439
00443 inline void
00444 orientationZaxisYCallback (const float& value) { orientation_ (2,1) = value; }
00445
00449 inline void
00450 orientationZaxisZCallback (const float& value) { orientation_ (2,2) = value; }
00451
00455 inline void
00456 cloudHeightCallback (const int &height) { cloud_->height = height; }
00457
00461 inline void
00462 cloudWidthCallback (const int &width) { cloud_->width = width; }
00463
00469 void
00470 appendDoubleProperty (const std::string& name, const size_t& count = 1);
00471
00477 void
00478 appendFloatProperty (const std::string& name, const size_t& count = 1);
00479
00485 void
00486 appendIntProperty (const std::string& name, const size_t& count = 1);
00487
00493 void
00494 appendUnsignedIntProperty (const std::string& name, const size_t& count = 1);
00495
00501 void
00502 appendShortProperty (const std::string& name, const size_t& count = 1);
00503
00509 void
00510 appendUnsignedShortProperty (const std::string& name, const size_t& count = 1);
00511
00517 void
00518 appendCharProperty (const std::string& name, const size_t& count = 1);
00519
00525 void
00526 appendUnsignedCharProperty (const std::string& name, const size_t& count = 1);
00527
00533 void
00534 amendProperty (const std::string& old_name, const std::string& new_name, uint8_t datatype = 0);
00535
00537 void
00538 vertexBeginCallback ();
00539
00541 void
00542 vertexEndCallback ();
00543
00545 void
00546 rangeGridBeginCallback ();
00547
00551 void
00552 rangeGridVertexIndicesBeginCallback (pcl::io::ply::uint8 size);
00553
00557 void
00558 rangeGridVertexIndicesElementCallback (pcl::io::ply::int32 vertex_index);
00559
00561 void
00562 rangeGridVertexIndicesEndCallback ();
00563
00565 void
00566 rangeGridEndCallback ();
00567
00569 void
00570 objInfoCallback (const std::string& line);
00571
00573 Eigen::Vector4f origin_;
00574
00576 Eigen::Matrix3f orientation_;
00577
00578
00579 pcl::PCLPointCloud2 *cloud_;
00580 size_t vertex_count_, vertex_properties_counter_;
00581 int vertex_offset_before_;
00582
00583 std::vector<std::vector <int> > *range_grid_;
00584 size_t range_count_, range_grid_vertex_indices_element_index_;
00585 size_t rgb_offset_before_;
00586 bool do_resize_;
00587 public:
00588 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00589 };
00590
00595 class PCL_EXPORTS PLYWriter : public FileWriter
00596 {
00597 public:
00599 PLYWriter () : FileWriter () {};
00600
00602 ~PLYWriter () {};
00603
00613 inline std::string
00614 generateHeaderBinary (const pcl::PCLPointCloud2 &cloud,
00615 const Eigen::Vector4f &origin,
00616 const Eigen::Quaternionf &orientation,
00617 int valid_points,
00618 bool use_camera = true)
00619 {
00620 return (generateHeader (cloud, origin, orientation, true, use_camera, valid_points));
00621 }
00622
00632 inline std::string
00633 generateHeaderASCII (const pcl::PCLPointCloud2 &cloud,
00634 const Eigen::Vector4f &origin,
00635 const Eigen::Quaternionf &orientation,
00636 int valid_points,
00637 bool use_camera = true)
00638 {
00639 return (generateHeader (cloud, origin, orientation, false, use_camera, valid_points));
00640 }
00641
00651 int
00652 writeASCII (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
00653 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
00654 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00655 int precision = 8,
00656 bool use_camera = true);
00657
00666 int
00667 writeBinary (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
00668 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
00669 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00670 bool use_camera = true);
00671
00680 inline int
00681 write (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
00682 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
00683 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00684 const bool binary = false)
00685 {
00686 if (binary)
00687 return (this->writeBinary (file_name, cloud, origin, orientation, true));
00688 else
00689 return (this->writeASCII (file_name, cloud, origin, orientation, 8, true));
00690 }
00691
00702 inline int
00703 write (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
00704 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
00705 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00706 bool binary = false,
00707 bool use_camera = true)
00708 {
00709 if (binary)
00710 return (this->writeBinary (file_name, cloud, origin, orientation, use_camera));
00711 else
00712 return (this->writeASCII (file_name, cloud, origin, orientation, 8, use_camera));
00713 }
00714
00725 inline int
00726 write (const std::string &file_name, const pcl::PCLPointCloud2::ConstPtr &cloud,
00727 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
00728 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00729 bool binary = false,
00730 bool use_camera = true)
00731 {
00732 return (write (file_name, *cloud, origin, orientation, binary, use_camera));
00733 }
00734
00743 template<typename PointT> inline int
00744 write (const std::string &file_name,
00745 const pcl::PointCloud<PointT> &cloud,
00746 bool binary = false,
00747 bool use_camera = true)
00748 {
00749 Eigen::Vector4f origin = cloud.sensor_origin_;
00750 Eigen::Quaternionf orientation = cloud.sensor_orientation_;
00751
00752 pcl::PCLPointCloud2 blob;
00753 pcl::toPCLPointCloud2 (cloud, blob);
00754
00755
00756 return (this->write (file_name, blob, origin, orientation, binary, use_camera));
00757 }
00758
00759 private:
00764 std::string
00765 generateHeader (const pcl::PCLPointCloud2 &cloud,
00766 const Eigen::Vector4f &origin,
00767 const Eigen::Quaternionf &orientation,
00768 bool binary,
00769 bool use_camera,
00770 int valid_points);
00771
00772 void
00773 writeContentWithCameraASCII (int nr_points,
00774 int point_size,
00775 const pcl::PCLPointCloud2 &cloud,
00776 const Eigen::Vector4f &origin,
00777 const Eigen::Quaternionf &orientation,
00778 std::ofstream& fs);
00779
00780 void
00781 writeContentWithRangeGridASCII (int nr_points,
00782 int point_size,
00783 const pcl::PCLPointCloud2 &cloud,
00784 std::ostringstream& fs,
00785 int& nb_valid_points);
00786 };
00787
00788 namespace io
00789 {
00799 inline int
00800 loadPLYFile (const std::string &file_name, pcl::PCLPointCloud2 &cloud)
00801 {
00802 pcl::PLYReader p;
00803 return (p.read (file_name, cloud));
00804 }
00805
00814 inline int
00815 loadPLYFile (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
00816 Eigen::Vector4f &origin, Eigen::Quaternionf &orientation)
00817 {
00818 pcl::PLYReader p;
00819 int ply_version;
00820 return (p.read (file_name, cloud, origin, orientation, ply_version));
00821 }
00822
00828 template<typename PointT> inline int
00829 loadPLYFile (const std::string &file_name, pcl::PointCloud<PointT> &cloud)
00830 {
00831 pcl::PLYReader p;
00832 return (p.read (file_name, cloud));
00833 }
00834
00843 inline int
00844 savePLYFile (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
00845 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
00846 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00847 bool binary_mode = false, bool use_camera = true)
00848 {
00849 PLYWriter w;
00850 return (w.write (file_name, cloud, origin, orientation, binary_mode, use_camera));
00851 }
00852
00860 template<typename PointT> inline int
00861 savePLYFile (const std::string &file_name, const pcl::PointCloud<PointT> &cloud, bool binary_mode = false)
00862 {
00863 PLYWriter w;
00864 return (w.write<PointT> (file_name, cloud, binary_mode));
00865 }
00866
00873 template<typename PointT> inline int
00874 savePLYFileASCII (const std::string &file_name, const pcl::PointCloud<PointT> &cloud)
00875 {
00876 PLYWriter w;
00877 return (w.write<PointT> (file_name, cloud, false));
00878 }
00879
00885 template<typename PointT> inline int
00886 savePLYFileBinary (const std::string &file_name, const pcl::PointCloud<PointT> &cloud)
00887 {
00888 PLYWriter w;
00889 return (w.write<PointT> (file_name, cloud, true));
00890 }
00891
00899 template<typename PointT> int
00900 savePLYFile (const std::string &file_name, const pcl::PointCloud<PointT> &cloud,
00901 const std::vector<int> &indices, bool binary_mode = false)
00902 {
00903
00904 pcl::PointCloud<PointT> cloud_out;
00905 copyPointCloud (cloud, indices, cloud_out);
00906
00907 PLYWriter w;
00908 return (w.write<PointT> (file_name, cloud_out, binary_mode));
00909 }
00910
00917 PCL_EXPORTS int
00918 savePLYFile (const std::string &file_name, const pcl::PolygonMesh &mesh, unsigned precision = 5);
00919
00925 PCL_EXPORTS int
00926 savePLYFileBinary (const std::string &file_name, const pcl::PolygonMesh &mesh);
00927 }
00928 }
00929
00930 #endif //#ifndef PCL_IO_PLY_IO_H_