pcd_io.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the copyright holder(s) nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id$
00037  *
00038  */
00039 
00040 #ifndef PCL_IO_PCD_IO_H_
00041 #define PCL_IO_PCD_IO_H_
00042 
00043 #include <pcl/point_cloud.h>
00044 #include <pcl/io/file_io.h>
00045 
00046 namespace pcl
00047 {
00052   class PCL_EXPORTS PCDReader : public FileReader
00053   {
00054     public:
00056       PCDReader () : FileReader () {}
00058       ~PCDReader () {}
00059 
00081       enum
00082       {
00083         PCD_V6 = 0,
00084         PCD_V7 = 1
00085       };
00086 
00114       int 
00115       readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
00116                   Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version,
00117                   int &data_type, unsigned int &data_idx, const int offset = 0);
00118 
00119 
00142       int 
00143       readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud, const int offset = 0);
00144 
00162       int 
00163       read (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
00164             Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version, const int offset = 0);
00165 
00186       int 
00187       read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, const int offset = 0);
00188 
00203       template<typename PointT> int
00204       read (const std::string &file_name, pcl::PointCloud<PointT> &cloud, const int offset = 0)
00205       {
00206         pcl::PCLPointCloud2 blob;
00207         int pcd_version;
00208         int res = read (file_name, blob, cloud.sensor_origin_, cloud.sensor_orientation_, 
00209                         pcd_version, offset);
00210 
00211         // If no error, convert the data
00212         if (res == 0)
00213           pcl::fromPCLPointCloud2 (blob, cloud);
00214         return (res);
00215       }
00216 
00217       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00218   };
00219 
00224   class PCL_EXPORTS PCDWriter : public FileWriter
00225   {
00226     public:
00227       PCDWriter() : FileWriter(), map_synchronization_(false) {}
00228       ~PCDWriter() {}
00229 
00238       void
00239       setMapSynchronization (bool sync)
00240       {
00241         map_synchronization_ = sync;
00242       }
00243 
00249       std::string
00250       generateHeaderBinary (const pcl::PCLPointCloud2 &cloud,
00251                             const Eigen::Vector4f &origin, 
00252                             const Eigen::Quaternionf &orientation);
00253 
00259       std::string
00260       generateHeaderBinaryCompressed (const pcl::PCLPointCloud2 &cloud,
00261                                       const Eigen::Vector4f &origin, 
00262                                       const Eigen::Quaternionf &orientation);
00263 
00269       std::string
00270       generateHeaderASCII (const pcl::PCLPointCloud2 &cloud,
00271                            const Eigen::Vector4f &origin, 
00272                            const Eigen::Quaternionf &orientation);
00273 
00279       template <typename PointT> static std::string
00280       generateHeader (const pcl::PointCloud<PointT> &cloud, 
00281                       const int nr_points = std::numeric_limits<int>::max ());
00282 
00299       int 
00300       writeASCII (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
00301                   const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), 
00302                   const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00303                   const int precision = 8);
00304 
00311       int 
00312       writeBinary (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
00313                    const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), 
00314                    const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity ());
00315 
00322       int 
00323       writeBinaryCompressed (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
00324                              const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), 
00325                              const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity ());
00326 
00344       inline int
00345       write (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
00346              const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), 
00347              const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00348              const bool binary = false)
00349       {
00350         if (binary)
00351           return (writeBinary (file_name, cloud, origin, orientation));
00352         else
00353           return (writeASCII (file_name, cloud, origin, orientation, 8));
00354       }
00355 
00371       inline int
00372       write (const std::string &file_name, const pcl::PCLPointCloud2::ConstPtr &cloud,
00373              const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), 
00374              const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00375              const bool binary = false)
00376       {
00377         return (write (file_name, *cloud, origin, orientation, binary));
00378       }
00379 
00384       template <typename PointT> int 
00385       writeBinary (const std::string &file_name, 
00386                    const pcl::PointCloud<PointT> &cloud);
00387 
00392       template <typename PointT> int 
00393       writeBinaryCompressed (const std::string &file_name, 
00394                              const pcl::PointCloud<PointT> &cloud);
00395 
00401       template <typename PointT> int 
00402       writeBinary (const std::string &file_name, 
00403                    const pcl::PointCloud<PointT> &cloud, 
00404                    const std::vector<int> &indices);
00405 
00411       template <typename PointT> int 
00412       writeASCII (const std::string &file_name, 
00413                   const pcl::PointCloud<PointT> &cloud,
00414                   const int precision = 8);
00415 
00422       template <typename PointT> int 
00423       writeASCII (const std::string &file_name, 
00424                   const pcl::PointCloud<PointT> &cloud,
00425                   const std::vector<int> &indices,
00426                   const int precision = 8);
00427 
00441       template<typename PointT> inline int
00442       write (const std::string &file_name, 
00443              const pcl::PointCloud<PointT> &cloud, 
00444              const bool binary = false)
00445       {
00446         if (binary)
00447           return (writeBinary<PointT> (file_name, cloud));
00448         else
00449           return (writeASCII<PointT> (file_name, cloud));
00450       }
00451 
00466       template<typename PointT> inline int
00467       write (const std::string &file_name, 
00468              const pcl::PointCloud<PointT> &cloud, 
00469              const std::vector<int> &indices,
00470              bool binary = false)
00471       {
00472         if (binary)
00473           return (writeBinary<PointT> (file_name, cloud, indices));
00474         else
00475           return (writeASCII<PointT> (file_name, cloud, indices));
00476       }
00477 
00478     protected:
00483       void
00484       setLockingPermissions (const std::string &file_name,
00485                              boost::interprocess::file_lock &lock);
00486 
00491       void
00492       resetLockingPermissions (const std::string &file_name,
00493                                boost::interprocess::file_lock &lock);
00494 
00495     private:
00497       bool map_synchronization_;
00498   };
00499 
00500   namespace io
00501   {
00511     inline int 
00512     loadPCDFile (const std::string &file_name, pcl::PCLPointCloud2 &cloud)
00513     {
00514       pcl::PCDReader p;
00515       return (p.read (file_name, cloud));
00516     }
00517 
00526     inline int 
00527     loadPCDFile (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
00528                  Eigen::Vector4f &origin, Eigen::Quaternionf &orientation)
00529     {
00530       pcl::PCDReader p;
00531       int pcd_version;
00532       return (p.read (file_name, cloud, origin, orientation, pcd_version));
00533     }
00534 
00540     template<typename PointT> inline int
00541     loadPCDFile (const std::string &file_name, pcl::PointCloud<PointT> &cloud)
00542     {
00543       pcl::PCDReader p;
00544       return (p.read (file_name, cloud));
00545     }
00546 
00562     inline int 
00563     savePCDFile (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
00564                  const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), 
00565                  const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00566                  const bool binary_mode = false)
00567     {
00568       PCDWriter w;
00569       return (w.write (file_name, cloud, origin, orientation, binary_mode));
00570     }
00571 
00586     template<typename PointT> inline int
00587     savePCDFile (const std::string &file_name, const pcl::PointCloud<PointT> &cloud, bool binary_mode = false)
00588     {
00589       PCDWriter w;
00590       return (w.write<PointT> (file_name, cloud, binary_mode));
00591     }
00592 
00609     template<typename PointT> inline int
00610     savePCDFileASCII (const std::string &file_name, const pcl::PointCloud<PointT> &cloud)
00611     {
00612       PCDWriter w;
00613       return (w.write<PointT> (file_name, cloud, false));
00614     }
00615 
00625     template<typename PointT> inline int
00626     savePCDFileBinary (const std::string &file_name, const pcl::PointCloud<PointT> &cloud)
00627     {
00628       PCDWriter w;
00629       return (w.write<PointT> (file_name, cloud, true));
00630     }
00631 
00649     template<typename PointT> int
00650     savePCDFile (const std::string &file_name, 
00651                  const pcl::PointCloud<PointT> &cloud,
00652                  const std::vector<int> &indices, 
00653                  const bool binary_mode = false)
00654     {
00655       // Save the data
00656       PCDWriter w;
00657       return (w.write<PointT> (file_name, cloud, indices, binary_mode));
00658     }
00659 
00660 
00670     template<typename PointT> inline int
00671     savePCDFileBinaryCompressed (const std::string &file_name, const pcl::PointCloud<PointT> &cloud)
00672     {
00673       PCDWriter w;
00674       return (w.writeBinaryCompressed<PointT> (file_name, cloud));
00675     }
00676 
00677   }
00678 }
00679 
00680 #include <pcl/io/impl/pcd_io.hpp>
00681 
00682 #endif  //#ifndef PCL_IO_PCD_IO_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:27:55