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 Willow Garage, Inc. 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: pcd_io.h 6122 2012-07-03 18:59:43Z aichim $
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 () {}
00080       enum
00081       {
00082         PCD_V6 = 0,
00083         PCD_V7 = 1
00084       };
00085 
00113       int 
00114       readHeader (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, 
00115                   Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version,
00116                   int &data_type, unsigned int &data_idx, const int offset = 0);
00117 
00118 
00141       int 
00142       readHeader (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, const int offset = 0);
00143 
00170       int 
00171       readHeaderEigen (const std::string &file_name, pcl::PointCloud<Eigen::MatrixXf> &cloud,
00172                        int &pcd_version, int &data_type, unsigned int &data_idx, const int offset = 0);
00173 
00191       int 
00192       read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, 
00193             Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version, const int offset = 0);
00194 
00215       int 
00216       read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, const int offset = 0);
00217 
00232       template<typename PointT> int
00233       read (const std::string &file_name, pcl::PointCloud<PointT> &cloud, const int offset = 0)
00234       {
00235         sensor_msgs::PointCloud2 blob;
00236         int pcd_version;
00237         int res = read (file_name, blob, cloud.sensor_origin_, cloud.sensor_orientation_, 
00238                         pcd_version, offset);
00239 
00240         // If no error, convert the data
00241         if (res == 0)
00242           pcl::fromROSMsg (blob, cloud);
00243         return (res);
00244       }
00245 
00263       int
00264       readEigen (const std::string &file_name, pcl::PointCloud<Eigen::MatrixXf> &cloud, const int offset = 0);
00265   };
00266 
00271   class PCL_EXPORTS PCDWriter : public FileWriter
00272   {
00273     public:
00274       PCDWriter() : FileWriter(), map_synchronization_(false) {}
00275       ~PCDWriter() {}
00276 
00285       void
00286       setMapSynchronization (bool sync)
00287       {
00288         map_synchronization_ = sync;
00289       }
00290 
00296       std::string
00297       generateHeaderBinary (const sensor_msgs::PointCloud2 &cloud, 
00298                             const Eigen::Vector4f &origin, 
00299                             const Eigen::Quaternionf &orientation);
00300 
00306       std::string
00307       generateHeaderBinaryCompressed (const sensor_msgs::PointCloud2 &cloud, 
00308                                       const Eigen::Vector4f &origin, 
00309                                       const Eigen::Quaternionf &orientation);
00310 
00316       std::string
00317       generateHeaderASCII (const sensor_msgs::PointCloud2 &cloud, 
00318                            const Eigen::Vector4f &origin, 
00319                            const Eigen::Quaternionf &orientation);
00320 
00326       template <typename PointT> static std::string
00327       generateHeader (const pcl::PointCloud<PointT> &cloud, 
00328                       const int nr_points = std::numeric_limits<int>::max ());
00329 
00339       std::string
00340       generateHeaderEigen (const pcl::PointCloud<Eigen::MatrixXf> &cloud, 
00341                            const int nr_points = std::numeric_limits<int>::max ());
00342 
00359       int 
00360       writeASCII (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud, 
00361                   const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), 
00362                   const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00363                   const int precision = 8);
00364 
00371       int 
00372       writeBinary (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud,
00373                    const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), 
00374                    const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity ());
00375 
00382       int 
00383       writeBinaryCompressed (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud,
00384                              const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), 
00385                              const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity ());
00386 
00404       inline int
00405       write (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud, 
00406              const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), 
00407              const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00408              const bool binary = false)
00409       {
00410         if (binary)
00411           return (writeBinary (file_name, cloud, origin, orientation));
00412         else
00413           return (writeASCII (file_name, cloud, origin, orientation, 8));
00414       }
00415 
00431       inline int
00432       write (const std::string &file_name, const sensor_msgs::PointCloud2::ConstPtr &cloud, 
00433              const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), 
00434              const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00435              const bool binary = false)
00436       {
00437         return (write (file_name, *cloud, origin, orientation, binary));
00438       }
00439 
00444       template <typename PointT> int 
00445       writeBinary (const std::string &file_name, 
00446                    const pcl::PointCloud<PointT> &cloud);
00447 
00456       int 
00457       writeBinaryEigen (const std::string &file_name, 
00458                         const pcl::PointCloud<Eigen::MatrixXf> &cloud);
00459 
00464       template <typename PointT> int 
00465       writeBinaryCompressed (const std::string &file_name, 
00466                              const pcl::PointCloud<PointT> &cloud);
00467 
00476       int 
00477       writeBinaryCompressedEigen (const std::string &file_name, 
00478                                   const pcl::PointCloud<Eigen::MatrixXf> &cloud);
00479 
00485       template <typename PointT> int 
00486       writeBinary (const std::string &file_name, 
00487                    const pcl::PointCloud<PointT> &cloud, 
00488                    const std::vector<int> &indices);
00489 
00495       template <typename PointT> int 
00496       writeASCII (const std::string &file_name, 
00497                   const pcl::PointCloud<PointT> &cloud,
00498                   const int precision = 8);
00499 
00509       int 
00510       writeASCIIEigen (const std::string &file_name, 
00511                        const pcl::PointCloud<Eigen::MatrixXf> &cloud,
00512                        const int precision = 8);
00513 
00520       template <typename PointT> int 
00521       writeASCII (const std::string &file_name, 
00522                   const pcl::PointCloud<PointT> &cloud,
00523                   const std::vector<int> &indices,
00524                   const int precision = 8);
00525 
00539       template<typename PointT> inline int
00540       write (const std::string &file_name, 
00541              const pcl::PointCloud<PointT> &cloud, 
00542              const bool binary = false)
00543       {
00544         if (binary)
00545           return (writeBinary<PointT> (file_name, cloud));
00546         else
00547           return (writeASCII<PointT> (file_name, cloud));
00548       }
00549 
00564       template<typename PointT> inline int
00565       write (const std::string &file_name, 
00566              const pcl::PointCloud<PointT> &cloud, 
00567              const std::vector<int> &indices,
00568              bool binary = false)
00569       {
00570         if (binary)
00571           return (writeBinary<PointT> (file_name, cloud, indices));
00572         else
00573           return (writeASCII<PointT> (file_name, cloud, indices));
00574       }
00575 
00576     private:
00578       bool map_synchronization_;
00579 
00580       typedef std::pair<std::string, pcl::ChannelProperties> pair_channel_properties;
00584       struct ChannelPropertiesComparator
00585       {
00586         bool 
00587         operator()(const pair_channel_properties &lhs, const pair_channel_properties &rhs) 
00588         {
00589           return (lhs.second.offset < rhs.second.offset);
00590         }
00591       };
00592   };
00593 
00594   namespace io
00595   {
00605     inline int 
00606     loadPCDFile (const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
00607     {
00608       pcl::PCDReader p;
00609       return (p.read (file_name, cloud));
00610     }
00611 
00620     inline int 
00621     loadPCDFile (const std::string &file_name, sensor_msgs::PointCloud2 &cloud,
00622                  Eigen::Vector4f &origin, Eigen::Quaternionf &orientation)
00623     {
00624       pcl::PCDReader p;
00625       int pcd_version;
00626       return (p.read (file_name, cloud, origin, orientation, pcd_version));
00627     }
00628 
00634     template<typename PointT> inline int
00635     loadPCDFile (const std::string &file_name, pcl::PointCloud<PointT> &cloud)
00636     {
00637       pcl::PCDReader p;
00638       return (p.read (file_name, cloud));
00639     }
00640 
00656     inline int 
00657     savePCDFile (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud, 
00658                  const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), 
00659                  const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00660                  const bool binary_mode = false)
00661     {
00662       PCDWriter w;
00663       return (w.write (file_name, cloud, origin, orientation, binary_mode));
00664     }
00665 
00680     template<typename PointT> inline int
00681     savePCDFile (const std::string &file_name, const pcl::PointCloud<PointT> &cloud, bool binary_mode = false)
00682     {
00683       PCDWriter w;
00684       return (w.write<PointT> (file_name, cloud, binary_mode));
00685     }
00686 
00703     template<typename PointT> inline int
00704     savePCDFileASCII (const std::string &file_name, const pcl::PointCloud<PointT> &cloud)
00705     {
00706       PCDWriter w;
00707       return (w.write<PointT> (file_name, cloud, false));
00708     }
00709 
00719     template<typename PointT> inline int
00720     savePCDFileBinary (const std::string &file_name, const pcl::PointCloud<PointT> &cloud)
00721     {
00722       PCDWriter w;
00723       return (w.write<PointT> (file_name, cloud, true));
00724     }
00725 
00743     template<typename PointT> int
00744     savePCDFile (const std::string &file_name, 
00745                  const pcl::PointCloud<PointT> &cloud,
00746                  const std::vector<int> &indices, 
00747                  const bool binary_mode = false)
00748     {
00749       // Save the data
00750       PCDWriter w;
00751       return (w.write<PointT> (file_name, cloud, indices, binary_mode));
00752     }
00753   }
00754 }
00755 
00756 #include <pcl/io/impl/pcd_io.hpp>
00757 
00758 #endif  //#ifndef PCL_IO_PCD_IO_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:16:24